aligator  0.9.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
expose-centroidal.cpp
Go to the documentation of this file.
1
15
16namespace aligator {
17namespace python {
18
19using context::Scalar;
24
26 bp::class_<ContactMap>(
27 "ContactMap", "Store contact state and pose for centroidal problem",
28 bp::init<const std::vector<std::string> &, const std::vector<bool> &,
29 const StdVectorEigenAligned<context::Vector3s> &>(
30 ("self"_a, "contact_names", "contact_states", "contact_poses")))
31 .def("addContact", &ContactMap::addContact,
32 ("self"_a, "name", "state", "pose"),
33 "Add a contact to the contact map.")
34 .def("removeContact", &ContactMap::removeContact, ("self"_a, "i"),
35 "Remove contact i from the contact map.")
36 .def("setContactPose", &ContactMap::setContactPose,
37 ("self"_a, "name", "ref"))
38 .def("getContactPose", &ContactMap::getContactPose, ("self"_a, "name"),
39 bp::return_internal_reference<>())
40 .def_readonly("size", &ContactMap::size_)
41 .def_readwrite("contact_states", &ContactMap::contact_states_)
42 .def_readwrite("contact_poses", &ContactMap::contact_poses_)
43 .def_readwrite("contact_names", &ContactMap::contact_names_);
44}
45
47 using CentroidalCoMResidual = CentroidalCoMResidualTpl<Scalar>;
48 using CentroidalCoMData = CentroidalCoMDataTpl<Scalar>;
49
50 using LinearMomentumResidual = LinearMomentumResidualTpl<Scalar>;
51 using LinearMomentumData = LinearMomentumDataTpl<Scalar>;
52
53 using AngularMomentumResidual = AngularMomentumResidualTpl<Scalar>;
54 using AngularMomentumData = AngularMomentumDataTpl<Scalar>;
55
56 using CentroidalAccelerationResidual =
58 using CentroidalAccelerationData = CentroidalAccelerationDataTpl<Scalar>;
59
60 using CentroidalFrictionConeResidual =
62 using CentroidalFrictionConeData = CentroidalFrictionConeDataTpl<Scalar>;
63
64 using CentroidalWrenchConeResidual = CentroidalWrenchConeResidualTpl<Scalar>;
65 using CentroidalWrenchConeData = CentroidalWrenchConeDataTpl<Scalar>;
66
67 using AngularAccelerationResidual = AngularAccelerationResidualTpl<Scalar>;
68 using AngularAccelerationData = AngularAccelerationDataTpl<Scalar>;
69
70 using CentroidalWrapperResidual = CentroidalWrapperResidualTpl<Scalar>;
71 using CentroidalWrapperData = CentroidalWrapperDataTpl<Scalar>;
72
75
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.")
85 .def(unary_visitor);
86
87 bp::register_ptr_to_python<shared_ptr<CentroidalCoMData>>();
88
89 bp::class_<CentroidalCoMData, bp::bases<StageFunctionData>>(
90 "CentroidalCoMData", "Data Structure for CentroidalCoM", bp::no_init);
91
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.")
100 .def(unary_visitor);
101
102 bp::register_ptr_to_python<shared_ptr<LinearMomentumData>>();
103
104 bp::class_<LinearMomentumData, bp::bases<StageFunctionData>>(
105 "LinearMomentumData", "Data Structure for LinearMomentum", bp::no_init);
106
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.")
116 .def(unary_visitor);
117
118 bp::register_ptr_to_python<shared_ptr<AngularMomentumData>>();
119
120 bp::class_<AngularMomentumData, bp::bases<StageFunctionData>>(
121 "AngularMomentumData", "Data Structure for AngularMomentum", bp::no_init);
122
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",
129 "force_size")))
130 .def_readwrite("contact_map",
131 &CentroidalAccelerationResidual::contact_map_)
133 .def(func_visitor);
134
135 bp::register_ptr_to_python<shared_ptr<CentroidalAccelerationData>>();
136
137 bp::class_<CentroidalAccelerationData, bp::bases<StageFunctionData>>(
138 "CentroidalAccelerationData", "Data Structure for CentroidalAcceleration",
139 bp::no_init);
140
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")))
146 .def(func_visitor);
147
148 bp::register_ptr_to_python<shared_ptr<CentroidalFrictionConeData>>();
149
150 bp::class_<CentroidalFrictionConeData, bp::bases<StageFunctionData>>(
151 "CentroidalFrictionConeData", "Data Structure for CentroidalFrictionCone",
152 bp::no_init);
153
154 bp::class_<CentroidalWrenchConeResidual, bp::bases<StageFunction>>(
155 "CentroidalWrenchConeResidual",
156 "A residual function :math:`r(x) = [fz, mu2 * fz2 - (fx2 + fy2)]` for "
157 "centroidal case ",
158 bp::init<const int, const int, const int, const double, const double,
159 const double>(("self"_a, "ndx", "nu", "k", "mu", "L", "W")))
160 .def(func_visitor);
161
162 bp::register_ptr_to_python<shared_ptr<CentroidalWrenchConeData>>();
163
164 bp::class_<CentroidalWrenchConeData, bp::bases<StageFunctionData>>(
165 "CentroidalWrenchConeData", "Data Structure for CentroidalWrenchCone",
166 bp::no_init);
167
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",
174 "force_size")))
175 .def_readwrite("contact_map", &AngularAccelerationResidual::contact_map_)
177 .def(func_visitor);
178
179 bp::register_ptr_to_python<shared_ptr<AngularAccelerationData>>();
180
181 bp::class_<AngularAccelerationData, bp::bases<StageFunctionData>>(
182 "AngularAccelerationData", "Data Structure for AngularAcceleration",
183 bp::no_init);
184
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_)
192 .def(unary_visitor);
193
194 bp::register_ptr_to_python<shared_ptr<CentroidalWrapperData>>();
195
196 bp::class_<CentroidalWrapperData, bp::bases<StageFunctionData>>(
197 "CentroidalWrapperData", "Data Structure for CentroidalWrapper",
198 bp::no_init);
199}
200
201} // namespace python
202} // namespace aligator
StageFunctionTpl< Scalar > StageFunction
Definition context.hpp:16
UnaryFunctionTpl< Scalar > UnaryFunction
Definition context.hpp:17
StageFunctionDataTpl< Scalar > StageFunctionData
Definition context.hpp:18
void exposeContactMap()
Centroidal cost functions.
const PolymorphicMultiBaseVisitor< UnaryFunction, StageFunction > unary_visitor
PolymorphicMultiBaseVisitor< StageFunction > func_visitor
Main package namespace.
This residual returns the angular acceleration of a centroidal model with state , computed from the e...
This residual returns the angular momentum for a centroidal model with state .
This residual returns the linear acceleration of a centroidal model with state , computed from the ex...
This residual implements the "ice cream" friction cone for a centroidal model with state .
This residual acts as a wrapper for centroidal model cost functions in which the external forces are ...
This residual implements the wrench cone for a centroidal model with control with 6D spatial force.
std::vector< bool > contact_states_
void addContact(const std::string &name, const bool state, const Vector3s &pose)
std::vector< std::string > contact_names_
const Vector3s & getContactPose(const std::string &name) const
void removeContact(const size_t i)
void setContactPose(const std::string &name, const Vector3s &ref)
This residual returns the linear momentum for a centroidal model with state .