56 using CentroidalAccelerationResidual =
60 using CentroidalFrictionConeResidual =
76 bp::class_<CentroidalCoMResidual, bp::bases<UnaryFunction>>(
77 "CentroidalCoMResidual",
"A residual function :math:`r(x) = com(x)` ",
78 bp::init<const int, const int, const context::Vector3s &>(
79 (
"self"_a,
"ndx",
"nu",
"p_ref")))
80 .def(
"getReference", &CentroidalCoMResidual::getReference, (
"self"_a),
81 bp::return_internal_reference<>(),
82 "Get the target Centroidal CoM translation.")
83 .def(
"setReference", &CentroidalCoMResidual::setReference,
84 (
"self"_a,
"p_new"),
"Set the target Centroidal CoM translation.")
87 bp::register_ptr_to_python<shared_ptr<CentroidalCoMData>>();
89 bp::class_<CentroidalCoMData, bp::bases<StageFunctionData>>(
90 "CentroidalCoMData",
"Data Structure for CentroidalCoM", bp::no_init);
92 bp::class_<LinearMomentumResidual, bp::bases<UnaryFunction>>(
93 "LinearMomentumResidual",
"A residual function :math:`r(x) = h(x)` ",
94 bp::init<const int, const int, const context::Vector3s &>(
95 (
"self"_a,
"ndx",
"nu",
"h_ref")))
96 .def(
"getReference", &LinearMomentumResidual::getReference, (
"self"_a),
97 bp::return_internal_reference<>(),
"Get the target Linear Momentum.")
98 .def(
"setReference", &LinearMomentumResidual::setReference,
99 (
"self"_a,
"h_new"),
"Set the target Linear Momentum.")
102 bp::register_ptr_to_python<shared_ptr<LinearMomentumData>>();
104 bp::class_<LinearMomentumData, bp::bases<StageFunctionData>>(
105 "LinearMomentumData",
"Data Structure for LinearMomentum", bp::no_init);
107 bp::class_<AngularMomentumResidual, bp::bases<UnaryFunction>>(
108 "AngularMomentumResidual",
"A residual function :math:`r(x) = L(x)` ",
109 bp::init<const int, const int, const context::Vector3s &>(
110 (
"self"_a,
"ndx",
"nu",
"L_ref")))
111 .def(
"getReference", &AngularMomentumResidual::getReference,
"self"_a,
112 bp::return_internal_reference<>(),
113 "Get the target Angular Momentum.")
114 .def(
"setReference", &AngularMomentumResidual::setReference,
115 (
"self"_a,
"L_new"),
"Set the target Angular Momentum.")
118 bp::register_ptr_to_python<shared_ptr<AngularMomentumData>>();
120 bp::class_<AngularMomentumData, bp::bases<StageFunctionData>>(
121 "AngularMomentumData",
"Data Structure for AngularMomentum", bp::no_init);
123 bp::class_<CentroidalAccelerationResidual, bp::bases<StageFunction>>(
124 "CentroidalAccelerationResidual",
125 "A residual function :math:`r(x) = cddot(x)` ",
126 bp::init<
const int,
const int,
const double,
const context::Vector3s &,
127 const ContactMap &,
const int>((
"self"_a,
"ndx",
"nu",
"mass",
128 "gravity",
"contact_map",
130 .def_readwrite(
"contact_map",
131 &CentroidalAccelerationResidual::contact_map_)
135 bp::register_ptr_to_python<shared_ptr<CentroidalAccelerationData>>();
137 bp::class_<CentroidalAccelerationData, bp::bases<StageFunctionData>>(
138 "CentroidalAccelerationData",
"Data Structure for CentroidalAcceleration",
141 bp::class_<CentroidalFrictionConeResidual, bp::bases<StageFunction>>(
142 "CentroidalFrictionConeResidual",
143 "A residual function :math:`r(x) = [fz, mu2 * fz2 - (fx2 + fy2)]` ",
144 bp::init<const int, const int, const int, const double, const double>(
145 (
"self"_a,
"ndx",
"nu",
"k",
"mu",
"epsilon")))
148 bp::register_ptr_to_python<shared_ptr<CentroidalFrictionConeData>>();
150 bp::class_<CentroidalFrictionConeData, bp::bases<StageFunctionData>>(
151 "CentroidalFrictionConeData",
"Data Structure for CentroidalFrictionCone",
154 bp::class_<CentroidalWrenchConeResidual, bp::bases<StageFunction>>(
155 "CentroidalWrenchConeResidual",
156 "A residual function :math:`r(x) = [fz, mu2 * fz2 - (fx2 + fy2)]` for "
158 bp::init<
const int,
const int,
const int,
const double,
const double,
159 const double>((
"self"_a,
"ndx",
"nu",
"k",
"mu",
"L",
"W")))
162 bp::register_ptr_to_python<shared_ptr<CentroidalWrenchConeData>>();
164 bp::class_<CentroidalWrenchConeData, bp::bases<StageFunctionData>>(
165 "CentroidalWrenchConeData",
"Data Structure for CentroidalWrenchCone",
168 bp::class_<AngularAccelerationResidual, bp::bases<StageFunction>>(
169 "AngularAccelerationResidual",
170 "A residual function :math:`r(x) = Ldot(x)` ",
171 bp::init<
const int,
const int,
const double,
const context::Vector3s &,
172 const ContactMap &,
const int>((
"self"_a,
"ndx",
"nu",
"mass",
173 "gravity",
"contact_map",
175 .def_readwrite(
"contact_map", &AngularAccelerationResidual::contact_map_)
179 bp::register_ptr_to_python<shared_ptr<AngularAccelerationData>>();
181 bp::class_<AngularAccelerationData, bp::bases<StageFunctionData>>(
182 "AngularAccelerationData",
"Data Structure for AngularAcceleration",
185 bp::class_<CentroidalWrapperResidual, bp::bases<UnaryFunction>>(
186 "CentroidalWrapperResidual",
187 "A wrapper for centroidal cost with smooth control",
188 bp::init<xyz::polymorphic<StageFunction>>((
"self"_a,
"centroidal_cost")))
189 .def_readwrite(
"centroidal_cost",
190 &CentroidalWrapperResidual::centroidal_cost_)
194 bp::register_ptr_to_python<shared_ptr<CentroidalWrapperData>>();
196 bp::class_<CentroidalWrapperData, bp::bases<StageFunctionData>>(
197 "CentroidalWrapperData",
"Data Structure for CentroidalWrapper",
StageFunctionTpl< Scalar > StageFunction
UnaryFunctionTpl< Scalar > UnaryFunction
StageFunctionDataTpl< Scalar > StageFunctionData