aligator 0.18.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;
29 pinocchio::RigidConstraintModelTpl<context::Scalar, 0>;
31 pinocchio::RigidConstraintDataTpl<context::Scalar, 0>;
32
34 PINOCCHIO_ALIGNED_STD_VECTOR(RigidConstraintModel);
36 PINOCCHIO_ALIGNED_STD_VECTOR(RigidConstraintData);
37
39
41 using ContactForceResidual = ContactForceResidualTpl<Scalar>;
42 using ContactForceData = ContactForceDataTpl<Scalar>;
43
44 using MultibodyWrenchConeResidual = MultibodyWrenchConeResidualTpl<Scalar>;
45 using MultibodyWrenchConeData = MultibodyWrenchConeDataTpl<Scalar>;
46
47 using MultibodyFrictionConeResidual =
49 using MultibodyFrictionConeData = MultibodyFrictionConeDataTpl<Scalar>;
50
51 bp::class_<ContactForceResidual, bp::bases<StageFunction>>(
52 "ContactForceResidual",
53 "A residual function :math:`r(x) = v_{j,xy} e^{-s z_j}` where :math:`j` "
54 "is a given frame index.",
55 bp::no_init)
56 .def(bp::init<int, PinModel, const context::MatrixXs &,
58 const pinocchio::ProximalSettingsTpl<Scalar> &,
59 const Eigen::VectorXd &, std::string_view>(bp::args(
60 "self", "ndx", "model", "actuation_matrix", "constraint_models",
61 "prox_settings", "fref", "contact_name")))
62 .def(func_visitor)
63 .def("getReference", &ContactForceResidual::getReference,
64 bp::args("self"), bp::return_internal_reference<>(),
65 "Get the target force.")
66 .def("setReference", &ContactForceResidual::setReference,
67 bp::args("self", "fnew"), "Set the target force.")
68 .def_readwrite("constraint_models",
69 &ContactForceResidual::constraint_models_);
70
71 bp::class_<ContactForceData, bp::bases<StageFunctionData>>("ContactForceData",
72 bp::no_init)
73 .def_readwrite("tau", &ContactForceData::tau_)
74 .def_readwrite("pin_data", &ContactForceData::pin_data_)
75 .def_readwrite("constraint_datas", &ContactForceData::constraint_datas_);
76
77 bp::class_<MultibodyWrenchConeResidual, bp::bases<StageFunction>>(
78 "MultibodyWrenchConeResidual", "A residual function :math:`r(x) = Af` ",
79 bp::no_init)
80 .def(bp::init<int, PinModel, const context::MatrixXs &,
82 const pinocchio::ProximalSettingsTpl<Scalar> &,
83 std::string_view, const double, const double, const double>(
84 bp::args("self", "ndx", "model", "actuation_matrix",
85 "constraint_models", "prox_settings", "contact_name", "mu",
86 "half_length", "half_width")))
87 .def(func_visitor)
88 .def_readwrite("constraint_models",
89 &MultibodyWrenchConeResidual::constraint_models_);
90
91 bp::class_<MultibodyWrenchConeData, bp::bases<StageFunctionData>>(
92 "MultibodyWrenchConeData", bp::no_init)
93 .def_readwrite("tau", &MultibodyWrenchConeData::tau_)
94 .def_readwrite("pin_data", &MultibodyWrenchConeData::pin_data_)
95 .def_readwrite("constraint_datas",
96 &MultibodyWrenchConeData::constraint_datas_);
97
98 bp::class_<MultibodyFrictionConeResidual, bp::bases<StageFunction>>(
99 "MultibodyFrictionConeResidual", "A residual function :math:`r(x) = Af` ",
100 bp::no_init)
101 .def(bp::init<int, PinModel, const context::MatrixXs &,
103 const pinocchio::ProximalSettingsTpl<Scalar> &,
104 std::string_view, const double>(
105 bp::args("self", "ndx", "model", "actuation_matrix",
106 "constraint_models", "prox_settings", "contact_name", "mu")))
107 .def(func_visitor)
108 .def_readwrite("constraint_models",
109 &MultibodyFrictionConeResidual::constraint_models_);
110
111 bp::class_<MultibodyFrictionConeData, bp::bases<StageFunctionData>>(
112 "MultibodyFrictionConeData", bp::no_init)
113 .def_readwrite("tau", &MultibodyFrictionConeData::tau_)
114 .def_readwrite("pin_data", &MultibodyFrictionConeData::pin_data_)
115 .def_readwrite("constraint_datas",
116 &MultibodyFrictionConeData::constraint_datas_);
117}
118
119} // namespace python
120} // namespace aligator
121
122#endif
pinocchio::ModelTpl< Scalar, Options > PinModel
Definition fwd.hpp:21
StageFunctionTpl< Scalar > StageFunction
Definition context.hpp:17
MultibodyPhaseSpace< Scalar > MultibodyPhaseSpace
Definition fwd.hpp:27
StageFunctionDataTpl< Scalar > StageFunctionData
Definition context.hpp:19
The Python bindings.
Definition blk-matrix.hpp:7
Eigen::Matrix< double, -1, 1, Eigen::ColMajor, 6, 1 > Vector3or6
pinocchio::RigidConstraintModelTpl< context::Scalar, 0 > RigidConstraintModel
PINOCCHIO_ALIGNED_STD_VECTOR(RigidConstraintModel) RigidConstraintModelVector
PINOCCHIO_ALIGNED_STD_VECTOR(RigidConstraintData) RigidConstraintDataVector
PolymorphicMultiBaseVisitor< StageFunction > func_visitor
pinocchio::RigidConstraintDataTpl< context::Scalar, 0 > RigidConstraintData
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.