21using Vector3or6 = Eigen::Matrix<double, -1, 1, Eigen::ColMajor, 6, 1>;
38 using MultibodyFrictionConeResidual =
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.",
47 .def(bp::init<
int,
PinModel,
const context::MatrixXs &,
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")))
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_);
62 bp::class_<ContactForceData, bp::bases<StageFunctionData>>(
"ContactForceData",
64 .def_readwrite(
"tau", &ContactForceData::tau_)
65 .def_readwrite(
"pin_data", &ContactForceData::pin_data_)
66 .def_readwrite(
"constraint_datas", &ContactForceData::constraint_datas_);
68 bp::class_<MultibodyWrenchConeResidual, bp::bases<StageFunction>>(
69 "MultibodyWrenchConeResidual",
"A residual function :math:`r(x) = Af` ",
71 .def(bp::init<
int,
PinModel,
const context::MatrixXs &,
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")))
79 .def_readwrite(
"constraint_models",
80 &MultibodyWrenchConeResidual::constraint_models_);
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_);
89 bp::class_<MultibodyFrictionConeResidual, bp::bases<StageFunction>>(
90 "MultibodyFrictionConeResidual",
"A residual function :math:`r(x) = Af` ",
92 .def(bp::init<
int,
PinModel,
const context::MatrixXs &,
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")))
99 .def_readwrite(
"constraint_models",
100 &MultibodyFrictionConeResidual::constraint_models_);
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_);
pinocchio::ModelTpl< Scalar, Options > PinModel
StageFunctionTpl< Scalar > StageFunction
MultibodyPhaseSpace< Scalar > MultibodyPhaseSpace
StageFunctionDataTpl< Scalar > StageFunctionData
PINOCCHIO_ALIGNED_STD_VECTOR(RCM) RCMVector
This residual returns the derivative of centroidal momentum for a kinodynamics model.
This residual returns the derivative of centroidal momentum for a kinodynamics model.