aligator  0.6.1
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
expose-center-of-mass.cpp
Go to the documentation of this file.
1
3#ifdef ALIGATOR_WITH_PINOCCHIO
5
11
12namespace aligator {
13namespace python {
14
17using context::Scalar;
21using ContactMap = ContactMapTpl<Scalar>;
22
23void exposeCenterOfMassFunctions() {
24 using CenterOfMassTranslation = CenterOfMassTranslationResidualTpl<Scalar>;
25 using CenterOfMassTranslationData = CenterOfMassTranslationDataTpl<Scalar>;
26
27 using CenterOfMassVelocity = CenterOfMassVelocityResidualTpl<Scalar>;
28 using CenterOfMassVelocityData = CenterOfMassVelocityDataTpl<Scalar>;
29
30 using CentroidalMomentumDerivativeResidual =
31 CentroidalMomentumDerivativeResidualTpl<Scalar>;
32 using CentroidalMomentumDerivativeData =
33 CentroidalMomentumDerivativeDataTpl<Scalar>;
34
35 using CentroidalMomentumResidual = CentroidalMomentumResidualTpl<Scalar>;
36 using CentroidalMomentumData = CentroidalMomentumDataTpl<Scalar>;
37
38 bp::class_<CenterOfMassTranslation, bp::bases<UnaryFunction>>(
39 "CenterOfMassTranslationResidual",
40 "A residual function :math:`r(x) = com(x)` ",
41 bp::init<const int, const int, shared_ptr<PinModel>,
42 const context::Vector3s>(
43 bp::args("self", "ndx", "nu", "model", "p_ref")))
44 .def(FrameAPIVisitor<CenterOfMassTranslation>())
45 .def("getReference", &CenterOfMassTranslation::getReference,
46 bp::args("self"), bp::return_internal_reference<>(),
47 "Get the target Center Of Mass translation.")
48 .def("setReference", &CenterOfMassTranslation::setReference,
49 bp::args("self", "p_new"),
50 "Set the target Center Of Mass translation.");
51
52 bp::register_ptr_to_python<shared_ptr<CenterOfMassTranslationData>>();
53
54 bp::class_<CenterOfMassTranslationData, bp::bases<StageFunctionData>>(
55 "CenterOfMassTranslationResidualData",
56 "Data Structure for CenterOfMassTranslation", bp::no_init)
57 .def_readonly("pin_data", &CenterOfMassTranslationData::pin_data_,
58 "Pinocchio data struct.");
59
60 bp::class_<CenterOfMassVelocity, bp::bases<UnaryFunction>>(
61 "CenterOfMassVelocityResidual",
62 "A residual function :math:`r(x) = vcom(x)` ",
63 bp::init<const int, const int, shared_ptr<PinModel>,
64 const context::Vector3s>(
65 bp::args("self", "ndx", "nu", "model", "v_ref")))
66 .def(FrameAPIVisitor<CenterOfMassVelocity>())
67 .def("getReference", &CenterOfMassVelocity::getReference,
68 bp::args("self"), bp::return_internal_reference<>(),
69 "Get the target Center Of Mass velocity.")
70 .def("setReference", &CenterOfMassVelocity::setReference,
71 bp::args("self", "p_new"),
72 "Set the target Center Of Mass velocity.");
73
74 bp::register_ptr_to_python<shared_ptr<CenterOfMassVelocityData>>();
75
76 bp::class_<CenterOfMassVelocityData, bp::bases<StageFunctionData>>(
77 "CenterOfMassVelocityResidualData",
78 "Data Structure for CenterOfMassVelocity", bp::no_init)
79 .def_readonly("pin_data", &CenterOfMassVelocityData::pin_data_,
80 "Pinocchio data struct.");
81
82 bp::class_<CentroidalMomentumDerivativeResidual, bp::bases<StageFunction>>(
83 "CentroidalMomentumDerivativeResidual",
84 "A residual function :math:`r(x) = H_dot` ",
85 bp::init<const int, const PinModel &, const context::Vector3s &,
86 const std::vector<bool> &,
87 const std::vector<pinocchio::FrameIndex> &, const int>(
88 bp::args("self", "ndx", "model", "gravity", "contact_states",
89 "contact_ids", "force_size")))
90 .def(FrameAPIVisitor<CentroidalMomentumDerivativeResidual>())
91 .def_readwrite("contact_states",
92 &CentroidalMomentumDerivativeResidual::contact_states_);
93
94 bp::register_ptr_to_python<shared_ptr<CentroidalMomentumDerivativeData>>();
95
96 bp::class_<CentroidalMomentumDerivativeData, bp::bases<StageFunctionData>>(
97 "CentroidalMomentumDerivativeResidualData",
98 "Data Structure for CentroidalMomentumDerivativeResidual", bp::no_init)
99 .def_readonly("pin_data", &CentroidalMomentumDerivativeData::pin_data_,
100 "Pinocchio data struct.");
101
102 bp::class_<CentroidalMomentumResidual, bp::bases<UnaryFunction>>(
103 "CentroidalMomentumResidual", "A residual function :math:`r(x) = H` ",
104 bp::init<const int, const int, const PinModel &,
105 const context::Vector6s &>(
106 bp::args("self", "ndx", "nu", "model", "h_ref")))
107 .def(FrameAPIVisitor<CentroidalMomentumResidual>())
108 .def("getReference", &CentroidalMomentumResidual::getReference,
109 bp::args("self"), bp::return_internal_reference<>(),
110 "Get the centroidal target.")
111 .def("setReference", &CentroidalMomentumResidual::setReference,
112 bp::args("self", "h_new"), "Set the centroidal target.");
113
114 bp::register_ptr_to_python<shared_ptr<CentroidalMomentumData>>();
115
116 bp::class_<CentroidalMomentumData, bp::bases<StageFunctionData>>(
117 "CentroidalMomentumResidualData",
118 "Data Structure for CentroidalMomentumResidual", bp::no_init)
119 .def_readonly("pin_data", &CentroidalMomentumData::pin_data_,
120 "Pinocchio data struct.");
121}
122
123} // namespace python
124} // namespace aligator
125
126#endif
pinocchio::ModelTpl< Scalar, Options > PinModel
Definition context.hpp:9
StageFunctionTpl< Scalar > StageFunction
Definition context.hpp:17
UnaryFunctionTpl< Scalar > UnaryFunction
Definition context.hpp:18
StageFunctionDataTpl< Scalar > StageFunctionData
Definition context.hpp:19
pinocchio::DataTpl< Scalar, Options > PinData
Definition context.hpp:10
ContactMapTpl< Scalar > ContactMap
Main package namespace.