aligator 0.19.0
A versatile and efficient C++ library for real-time constrained trajectory optimization.
Loading...
Searching...
No Matches
expose-force-cost.cpp
Go to the documentation of this file.
1
3#ifdef ALIGATOR_WITH_PINOCCHIO
4
5// Boost.Python 1.74 include manually mpl/vector/vector20.hpp
6// that prevent us to define mpl::list and mpl::vector with
7// the right size.
8// To avoid this issue this header should be included first.
9#include <pinocchio/fwd.hpp>
10
13
17
18namespace aligator {
19namespace python {
20
21using Vector3or6 = Eigen::Matrix<double, -1, 1, Eigen::ColMajor, 6, 1>;
22using context::ConstVectorRef;
25using context::Scalar;
28
30
32 using ContactForceResidual = ContactForceResidualTpl<Scalar>;
33 using ContactForceData = ContactForceDataTpl<Scalar>;
34
35 using MultibodyWrenchConeResidual = MultibodyWrenchConeResidualTpl<Scalar>;
36 using MultibodyWrenchConeData = MultibodyWrenchConeDataTpl<Scalar>;
37
38 using MultibodyFrictionConeResidual =
40 using MultibodyFrictionConeData = MultibodyFrictionConeDataTpl<Scalar>;
41
42 bp::class_<ContactForceResidual, bp::bases<StageFunction>>(
43 "ContactForceResidual",
44 "A residual function :math:`r(x) = v_{j,xy} e^{-s z_j}` where :math:`j` "
45 "is a given frame index.",
46 bp::no_init)
47 .def(bp::init<int, PinModel, const context::MatrixXs &,
48 const context::RCMVector &,
49 const pinocchio::ProximalSettingsTpl<Scalar> &,
50 const Eigen::VectorXd &, std::string_view>(bp::args(
51 "self", "ndx", "model", "actuation_matrix", "constraint_models",
52 "prox_settings", "fref", "contact_name")))
53 .def(func_visitor)
54 .def("getReference", &ContactForceResidual::getReference,
55 bp::args("self"), bp::return_internal_reference<>(),
56 "Get the target force.")
57 .def("setReference", &ContactForceResidual::setReference,
58 bp::args("self", "fnew"), "Set the target force.")
59 .def_readwrite("constraint_models",
60 &ContactForceResidual::constraint_models_);
61
62 bp::class_<ContactForceData, bp::bases<StageFunctionData>>("ContactForceData",
63 bp::no_init)
64 .def_readwrite("tau", &ContactForceData::tau_)
65 .def_readwrite("pin_data", &ContactForceData::pin_data_)
66 .def_readwrite("constraint_datas", &ContactForceData::constraint_datas_);
67
68 bp::class_<MultibodyWrenchConeResidual, bp::bases<StageFunction>>(
69 "MultibodyWrenchConeResidual", "A residual function :math:`r(x) = Af` ",
70 bp::no_init)
71 .def(bp::init<int, PinModel, const context::MatrixXs &,
72 const context::RCMVector &,
73 const pinocchio::ProximalSettingsTpl<Scalar> &,
74 std::string_view, const double, const double, const double>(
75 bp::args("self", "ndx", "model", "actuation_matrix",
76 "constraint_models", "prox_settings", "contact_name", "mu",
77 "half_length", "half_width")))
78 .def(func_visitor)
79 .def_readwrite("constraint_models",
80 &MultibodyWrenchConeResidual::constraint_models_);
81
82 bp::class_<MultibodyWrenchConeData, bp::bases<StageFunctionData>>(
83 "MultibodyWrenchConeData", bp::no_init)
84 .def_readwrite("tau", &MultibodyWrenchConeData::tau_)
85 .def_readwrite("pin_data", &MultibodyWrenchConeData::pin_data_)
86 .def_readwrite("constraint_datas",
87 &MultibodyWrenchConeData::constraint_datas_);
88
89 bp::class_<MultibodyFrictionConeResidual, bp::bases<StageFunction>>(
90 "MultibodyFrictionConeResidual", "A residual function :math:`r(x) = Af` ",
91 bp::no_init)
92 .def(bp::init<int, PinModel, const context::MatrixXs &,
93 const context::RCMVector &,
94 const pinocchio::ProximalSettingsTpl<Scalar> &,
95 std::string_view, const double>(
96 bp::args("self", "ndx", "model", "actuation_matrix",
97 "constraint_models", "prox_settings", "contact_name", "mu")))
98 .def(func_visitor)
99 .def_readwrite("constraint_models",
100 &MultibodyFrictionConeResidual::constraint_models_);
101
102 bp::class_<MultibodyFrictionConeData, bp::bases<StageFunctionData>>(
103 "MultibodyFrictionConeData", bp::no_init)
104 .def_readwrite("tau", &MultibodyFrictionConeData::tau_)
105 .def_readwrite("pin_data", &MultibodyFrictionConeData::pin_data_)
106 .def_readwrite("constraint_datas",
107 &MultibodyFrictionConeData::constraint_datas_);
108}
109
110} // namespace python
111} // namespace aligator
112
113#endif
pinocchio::ModelTpl< Scalar, Options > PinModel
Definition fwd.hpp:21
StageFunctionTpl< Scalar > StageFunction
Definition context.hpp:17
MultibodyPhaseSpace< Scalar > MultibodyPhaseSpace
Definition fwd.hpp:29
StageFunctionDataTpl< Scalar > StageFunctionData
Definition context.hpp:19
PINOCCHIO_ALIGNED_STD_VECTOR(RCM) RCMVector
Definition fwd.hpp:26
The Python bindings.
Definition blk-matrix.hpp:7
Eigen::Matrix< double, -1, 1, Eigen::ColMajor, 6, 1 > Vector3or6
PolymorphicMultiBaseVisitor< StageFunction > func_visitor
Main package namespace.
This residual returns the derivative of centroidal momentum for a kinodynamics model.
This residual returns the derivative of centroidal momentum for a kinodynamics model.
This residual returns the derivative of centroidal momentum for a kinodynamics model.