3#ifdef ALIGATOR_WITH_PINOCCHIO
23void exposeCenterOfMassFunctions() {
24 using CenterOfMassTranslation = CenterOfMassTranslationResidualTpl<Scalar>;
25 using CenterOfMassTranslationData = CenterOfMassTranslationDataTpl<Scalar>;
27 using CenterOfMassVelocity = CenterOfMassVelocityResidualTpl<Scalar>;
28 using CenterOfMassVelocityData = CenterOfMassVelocityDataTpl<Scalar>;
30 using DCMPosition = DCMPositionResidualTpl<Scalar>;
31 using DCMPositionData = DCMPositionDataTpl<Scalar>;
33 using CentroidalMomentumDerivativeResidual =
34 CentroidalMomentumDerivativeResidualTpl<Scalar>;
35 using CentroidalMomentumDerivativeData =
36 CentroidalMomentumDerivativeDataTpl<Scalar>;
38 using CentroidalMomentumResidual = CentroidalMomentumResidualTpl<Scalar>;
39 using CentroidalMomentumData = CentroidalMomentumDataTpl<Scalar>;
42 PolymorphicMultiBaseVisitor<UnaryFunction, StageFunction>
unary_visitor;
44 bp::class_<CenterOfMassTranslation, bp::bases<UnaryFunction>>(
45 "CenterOfMassTranslationResidual",
46 "A residual function :math:`r(x) = com(x)` ",
47 bp::init<const int, const int, const PinModel &, const context::Vector3s>(
48 bp::args(
"self",
"ndx",
"nu",
"model",
"p_ref")))
49 .def(FrameAPIVisitor<CenterOfMassTranslation>())
50 .def(
"getReference", &CenterOfMassTranslation::getReference,
51 bp::args(
"self"), bp::return_internal_reference<>(),
52 "Get the target Center Of Mass translation.")
53 .def(
"setReference", &CenterOfMassTranslation::setReference,
54 bp::args(
"self",
"p_new"),
55 "Set the target Center Of Mass translation.")
58 bp::register_ptr_to_python<shared_ptr<CenterOfMassTranslationData>>();
60 bp::class_<CenterOfMassTranslationData, bp::bases<StageFunctionData>>(
61 "CenterOfMassTranslationResidualData",
62 "Data Structure for CenterOfMassTranslation", bp::no_init)
63 .def_readonly(
"pin_data", &CenterOfMassTranslationData::pin_data_,
64 "Pinocchio data struct.");
66 bp::class_<CenterOfMassVelocity, bp::bases<UnaryFunction>>(
67 "CenterOfMassVelocityResidual",
68 "A residual function :math:`r(x) = vcom(x)` ",
69 bp::init<const int, const int, const PinModel &, const context::Vector3s>(
70 bp::args(
"self",
"ndx",
"nu",
"model",
"v_ref")))
71 .def(FrameAPIVisitor<CenterOfMassVelocity>())
73 .def(
"getReference", &CenterOfMassVelocity::getReference,
74 bp::args(
"self"), bp::return_internal_reference<>(),
75 "Get the target Center Of Mass velocity.")
76 .def(
"setReference", &CenterOfMassVelocity::setReference,
77 bp::args(
"self",
"p_new"),
78 "Set the target Center Of Mass velocity.");
80 bp::register_ptr_to_python<shared_ptr<CenterOfMassVelocityData>>();
82 bp::class_<CenterOfMassVelocityData, bp::bases<StageFunctionData>>(
83 "CenterOfMassVelocityResidualData",
84 "Data Structure for CenterOfMassVelocity", bp::no_init)
85 .def_readonly(
"pin_data", &CenterOfMassVelocityData::pin_data_,
86 "Pinocchio data struct.");
88 bp::class_<DCMPosition, bp::bases<UnaryFunction>>(
89 "DCMPositionResidual",
"A residual function :math:`r(x) = dcm(x)` ",
90 bp::init<
const int,
const int,
const PinModel &,
91 const context::Vector3s &,
const double>(
92 bp::args(
"self",
"ndx",
"nu",
"model",
"dcm_ref",
"alpha")))
93 .def(FrameAPIVisitor<DCMPosition>())
95 .def(
"getReference", &DCMPosition::getReference, bp::args(
"self"),
96 bp::return_internal_reference<>(),
"Get the target DCM position.")
97 .def(
"setReference", &DCMPosition::setReference,
98 bp::args(
"self",
"new_ref"),
"Set the target DCM position.");
100 bp::register_ptr_to_python<shared_ptr<DCMPositionData>>();
102 bp::class_<DCMPositionData, bp::bases<StageFunctionData>>(
103 "DCMPositionResidualData",
"Data Structure for DCMPosition", bp::no_init)
104 .def_readonly(
"pin_data", &DCMPositionData::pin_data_,
105 "Pinocchio data struct.");
107 bp::class_<CentroidalMomentumDerivativeResidual, bp::bases<StageFunction>>(
108 "CentroidalMomentumDerivativeResidual",
109 "A residual function :math:`r(x) = H_dot` ",
110 bp::init<
const int,
const PinModel &,
const context::Vector3s &,
111 const std::vector<bool> &,
112 const std::vector<pinocchio::FrameIndex> &,
const int>(
113 bp::args(
"self",
"ndx",
"model",
"gravity",
"contact_states",
114 "contact_ids",
"force_size")))
116 .def_readwrite(
"contact_states",
117 &CentroidalMomentumDerivativeResidual::contact_states_);
119 bp::register_ptr_to_python<shared_ptr<CentroidalMomentumDerivativeData>>();
121 bp::class_<CentroidalMomentumDerivativeData, bp::bases<StageFunctionData>>(
122 "CentroidalMomentumDerivativeResidualData",
123 "Data Structure for CentroidalMomentumDerivativeResidual", bp::no_init)
124 .def_readonly(
"pin_data", &CentroidalMomentumDerivativeData::pin_data_,
125 "Pinocchio data struct.");
127 bp::class_<CentroidalMomentumResidual, bp::bases<UnaryFunction>>(
128 "CentroidalMomentumResidual",
"A residual function :math:`r(x) = H` ",
129 bp::init<
const int,
const int,
const PinModel &,
130 const context::Vector6s &>(
131 bp::args(
"self",
"ndx",
"nu",
"model",
"h_ref")))
133 .def(
"getReference", &CentroidalMomentumResidual::getReference,
134 bp::args(
"self"), bp::return_internal_reference<>(),
135 "Get the centroidal target.")
136 .def(
"setReference", &CentroidalMomentumResidual::setReference,
137 bp::args(
"self",
"h_new"),
"Set the centroidal target.");
139 bp::register_ptr_to_python<shared_ptr<CentroidalMomentumData>>();
141 bp::class_<CentroidalMomentumData, bp::bases<StageFunctionData>>(
142 "CentroidalMomentumResidualData",
143 "Data Structure for CentroidalMomentumResidual", bp::no_init)
144 .def_readonly(
"pin_data", &CentroidalMomentumData::pin_data_,
145 "Pinocchio data struct.");
pinocchio::ModelTpl< Scalar, Options > PinModel
StageFunctionTpl< Scalar > StageFunction
UnaryFunctionTpl< Scalar > UnaryFunction
StageFunctionDataTpl< Scalar > StageFunctionData
pinocchio::DataTpl< Scalar, Options > PinData
const PolymorphicMultiBaseVisitor< UnaryFunction, StageFunction > unary_visitor
PolymorphicMultiBaseVisitor< StageFunction > func_visitor