Line |
Branch |
Exec |
Source |
1 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
2 |
|
|
// BSD 3-Clause License |
3 |
|
|
// |
4 |
|
|
// Copyright (C) 2019-2025, LAAS-CNRS, University of Edinburgh, |
5 |
|
|
// Heriot-Watt University |
6 |
|
|
// Copyright note valid unless otherwise stated in individual files. |
7 |
|
|
// All rights reserved. |
8 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
9 |
|
|
|
10 |
|
|
// Auto-generated file for float |
11 |
|
|
#include "crocoddyl/multibody/residuals/contact-force.hpp" |
12 |
|
|
|
13 |
|
|
#include "python/crocoddyl/multibody/multibody.hpp" |
14 |
|
|
#include "python/crocoddyl/utils/deprecate.hpp" |
15 |
|
|
|
16 |
|
|
namespace crocoddyl { |
17 |
|
|
namespace python { |
18 |
|
|
|
19 |
|
|
template <typename Model> |
20 |
|
|
struct ResidualModelContactForceVisitor |
21 |
|
|
: public bp::def_visitor<ResidualModelContactForceVisitor<Model>> { |
22 |
|
|
typedef typename Model::ResidualDataAbstract Data; |
23 |
|
|
typedef typename Model::StateMultibody State; |
24 |
|
|
typedef typename Model::Force Force; |
25 |
|
|
typedef typename Model::VectorXs VectorXs; |
26 |
|
|
template <class PyClass> |
27 |
|
✗ |
void visit(PyClass& cl) const { |
28 |
|
✗ |
cl.def(bp::init<std::shared_ptr<State>, pinocchio::FrameIndex, Force, |
29 |
|
|
std::size_t>( |
30 |
|
|
bp::args("self", "state", "id", "fref", "nc"), |
31 |
|
|
"Initialize the contact force residual model.\n\n" |
32 |
|
|
"The default nu is obtained from state.nv. Note that this " |
33 |
|
|
"constructor can be used for forward-dynamics cases only.\n" |
34 |
|
|
":param state: state of the multibody system\n" |
35 |
|
|
":param id: reference frame id\n" |
36 |
|
|
":param nc: dimension of the contact force (nc <= 6)\n" |
37 |
|
|
":param fref: reference spatial contact force in the contact " |
38 |
|
|
"coordinates\n")) |
39 |
|
✗ |
.def( |
40 |
|
|
"calc", |
41 |
|
|
static_cast<void (Model::*)( |
42 |
|
|
const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, |
43 |
|
|
const Eigen::Ref<const VectorXs>&)>(&Model::calc), |
44 |
|
|
bp::args("self", "data", "x", "u"), |
45 |
|
|
"Compute the contact force residual.\n\n" |
46 |
|
|
":param data: residual data\n" |
47 |
|
|
":param x: state point (dim. state.nx)\n" |
48 |
|
|
":param u: control input (dim. nu)") |
49 |
|
✗ |
.def("calc", |
50 |
|
|
static_cast<void (Model::*)(const std::shared_ptr<Data>&, |
51 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
52 |
|
|
&Model::calc), |
53 |
|
|
bp::args("self", "data", "x")) |
54 |
|
✗ |
.def( |
55 |
|
|
"calcDiff", |
56 |
|
|
static_cast<void (Model::*)( |
57 |
|
|
const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, |
58 |
|
|
const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff), |
59 |
|
|
bp::args("self", "data", "x", "u"), |
60 |
|
|
"Compute the Jacobians of the contact force residual.\n\n" |
61 |
|
|
"It assumes that calc has been run first.\n" |
62 |
|
|
":param data: action data\n" |
63 |
|
|
":param x: state point (dim. state.nx)\n" |
64 |
|
|
":param u: control input (dim. nu)") |
65 |
|
✗ |
.def("calcDiff", |
66 |
|
|
static_cast<void (Model::*)(const std::shared_ptr<Data>&, |
67 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
68 |
|
|
&Model::calcDiff), |
69 |
|
|
bp::args("self", "data", "x")) |
70 |
|
✗ |
.def("createData", &Model::createData, |
71 |
|
✗ |
bp::with_custodian_and_ward_postcall<0, 2>(), |
72 |
|
|
bp::args("self", "data"), |
73 |
|
|
"Create the contact force residual data.\n\n" |
74 |
|
|
"Each residual model has its own data that needs to be allocated. " |
75 |
|
|
"This function returns the allocated data for the contact force " |
76 |
|
|
"residual.\n" |
77 |
|
|
":param data: shared data\n" |
78 |
|
|
":return residual data.") |
79 |
|
✗ |
.add_property( |
80 |
|
|
"id", bp::make_function(&Model::get_id), |
81 |
|
|
bp::make_function(&Model::set_id, |
82 |
|
✗ |
deprecated<>("Deprecated. Do not use set_id, " |
83 |
|
|
"instead create a new model")), |
84 |
|
|
"reference frame id") |
85 |
|
✗ |
.add_property("reference", |
86 |
|
|
bp::make_function( |
87 |
|
|
&Model::get_reference, |
88 |
|
✗ |
bp::return_value_policy<bp::copy_const_reference>()), |
89 |
|
|
&Model::set_reference, "reference spatial force"); |
90 |
|
|
} |
91 |
|
|
}; |
92 |
|
|
|
93 |
|
|
template <typename Data> |
94 |
|
|
struct ResidualDataContactForceVisitor |
95 |
|
|
: public bp::def_visitor<ResidualDataContactForceVisitor<Data>> { |
96 |
|
|
template <class PyClass> |
97 |
|
✗ |
void visit(PyClass& cl) const { |
98 |
|
✗ |
cl.add_property( |
99 |
|
|
"contact", |
100 |
|
|
bp::make_getter(&Data::contact, |
101 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
102 |
|
|
bp::make_setter(&Data::contact), |
103 |
|
|
"contact data associated with the current residual"); |
104 |
|
|
} |
105 |
|
|
}; |
106 |
|
|
|
107 |
|
|
#define CROCODDYL_RESIDUAL_MODEL_CONTACT_FORCE_PYTHON_BINDINGS(Scalar) \ |
108 |
|
|
typedef ResidualModelContactForceTpl<Scalar> Model; \ |
109 |
|
|
typedef ResidualModelAbstractTpl<Scalar> ModelBase; \ |
110 |
|
|
typedef typename Model::StateMultibody State; \ |
111 |
|
|
typedef typename Model::Force Force; \ |
112 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ |
113 |
|
|
bp::class_<Model, bp::bases<ModelBase>>( \ |
114 |
|
|
"ResidualModelContactForce", \ |
115 |
|
|
"This residual function is defined as r = f-fref, where f,fref " \ |
116 |
|
|
"describe the current and reference the spatial forces, respectively.", \ |
117 |
|
|
bp::init<std::shared_ptr<State>, pinocchio::FrameIndex, Force, \ |
118 |
|
|
std::size_t, std::size_t, bp::optional<bool>>( \ |
119 |
|
|
bp::args("self", "state", "id", "fref", "nc", "nu", "fwddyn"), \ |
120 |
|
|
"Initialize the contact force residual model.\n\n" \ |
121 |
|
|
":param state: state of the multibody system\n" \ |
122 |
|
|
":param id: reference frame id\n" \ |
123 |
|
|
":param fref: reference spatial contact force in the contact " \ |
124 |
|
|
"coordinates\n" \ |
125 |
|
|
":param nc: dimension of the contact force (nc <= 6)\n" \ |
126 |
|
|
":param nu: dimension of control vector\n" \ |
127 |
|
|
":param fwddyn: indicate if we have a forward dynamics problem " \ |
128 |
|
|
"(True) or inverse dynamics problem (False) (default True)")) \ |
129 |
|
|
.def(ResidualModelContactForceVisitor<Model>()) \ |
130 |
|
|
.def(CastVisitor<Model>()) \ |
131 |
|
|
.def(PrintableVisitor<Model>()) \ |
132 |
|
|
.def(CopyableVisitor<Model>()); |
133 |
|
|
|
134 |
|
|
#define CROCODDYL_RESIDUAL_DATA_CONTACT_FORCE_PYTHON_BINDINGS(Scalar) \ |
135 |
|
|
typedef ResidualDataContactForceTpl<Scalar> Data; \ |
136 |
|
|
typedef ResidualDataAbstractTpl<Scalar> DataBase; \ |
137 |
|
|
typedef ResidualModelContactForceTpl<Scalar> Model; \ |
138 |
|
|
typedef Model::DataCollectorAbstract DataCollector; \ |
139 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Data>>(); \ |
140 |
|
|
bp::class_<Data, bp::bases<DataBase>>( \ |
141 |
|
|
"ResidualDataContactForce", "Data for contact force residual.\n\n", \ |
142 |
|
|
bp::init<Model*, DataCollector*>( \ |
143 |
|
|
bp::args("self", "model", "data"), \ |
144 |
|
|
"Create contact force residual data.\n\n" \ |
145 |
|
|
":param model: contact force residual model\n" \ |
146 |
|
|
":param data: shared data")[bp::with_custodian_and_ward< \ |
147 |
|
|
1, 2, bp::with_custodian_and_ward<1, 3>>()]) \ |
148 |
|
|
.def(ResidualDataContactForceVisitor<Data>()) \ |
149 |
|
|
.def(CopyableVisitor<Data>()); |
150 |
|
|
|
151 |
|
✗ |
void exposeResidualContactForce() { |
152 |
|
✗ |
CROCODDYL_RESIDUAL_MODEL_CONTACT_FORCE_PYTHON_BINDINGS(float) |
153 |
|
✗ |
CROCODDYL_RESIDUAL_DATA_CONTACT_FORCE_PYTHON_BINDINGS(float) |
154 |
|
|
} |
155 |
|
|
|
156 |
|
|
} // namespace python |
157 |
|
|
} // namespace crocoddyl |
158 |
|
|
|