Line |
Branch |
Exec |
Source |
1 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
2 |
|
|
// BSD 3-Clause License |
3 |
|
|
// |
4 |
|
|
// Copyright (C) 2021-2025, University of Edinburgh, Heriot-Watt University |
5 |
|
|
// Copyright note valid unless otherwise stated in individual files. |
6 |
|
|
// All rights reserved. |
7 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
8 |
|
|
|
9 |
|
|
// Auto-generated file for double |
10 |
|
|
#include "crocoddyl/multibody/residuals/com-position.hpp" |
11 |
|
|
|
12 |
|
|
#include "python/crocoddyl/multibody/multibody.hpp" |
13 |
|
|
|
14 |
|
|
namespace crocoddyl { |
15 |
|
|
namespace python { |
16 |
|
|
|
17 |
|
|
template <typename Model> |
18 |
|
|
struct ResidualModelCoMPositionVisitor |
19 |
|
|
: public bp::def_visitor<ResidualModelCoMPositionVisitor<Model>> { |
20 |
|
|
typedef typename Model::ResidualDataAbstract Data; |
21 |
|
|
typedef typename Model::Base ModelBase; |
22 |
|
|
typedef typename Model::StateMultibody State; |
23 |
|
|
typedef typename Model::VectorXs VectorXs; |
24 |
|
|
typedef typename Model::Vector3s Vector3s; |
25 |
|
|
template <class PyClass> |
26 |
|
✗ |
void visit(PyClass& cl) const { |
27 |
|
✗ |
cl.def(bp::init<std::shared_ptr<State>, Vector3s>( |
28 |
|
|
bp::args("self", "state", "cref"), |
29 |
|
|
"Initialize the CoM position residual model.\n\n" |
30 |
|
|
"The default nu is obtained from state.nv.\n" |
31 |
|
|
":param state: state of the multibody system\n" |
32 |
|
|
":param cref: reference CoM position")) |
33 |
|
✗ |
.def( |
34 |
|
|
"calc", |
35 |
|
|
static_cast<void (Model::*)( |
36 |
|
|
const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, |
37 |
|
|
const Eigen::Ref<const VectorXs>&)>(&Model::calc), |
38 |
|
|
bp::args("self", "data", "x", "u"), |
39 |
|
|
"Compute the CoM position residual.\n\n" |
40 |
|
|
":param data: residual data\n" |
41 |
|
|
":param x: state point (dim. state.nx)\n" |
42 |
|
|
":param u: control input (dim. nu)") |
43 |
|
✗ |
.def( |
44 |
|
|
"calc", |
45 |
|
|
static_cast<void (ModelBase::*)(const std::shared_ptr<Data>&, |
46 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
47 |
|
|
&ModelBase::calc), |
48 |
|
|
bp::args("self", "data", "x")) |
49 |
|
✗ |
.def( |
50 |
|
|
"calcDiff", |
51 |
|
|
static_cast<void (Model::*)( |
52 |
|
|
const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, |
53 |
|
|
const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff), |
54 |
|
|
bp::args("self", "data", "x", "u"), |
55 |
|
|
"Compute the Jacobians of the CoM position residual.\n\n" |
56 |
|
|
"It assumes that calc has been run first.\n" |
57 |
|
|
":param data: action data\n" |
58 |
|
|
":param x: state point (dim. state.nx)\n" |
59 |
|
|
":param u: control input (dim. nu)") |
60 |
|
✗ |
.def( |
61 |
|
|
"calcDiff", |
62 |
|
|
static_cast<void (ModelBase::*)(const std::shared_ptr<Data>&, |
63 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
64 |
|
|
&ModelBase::calcDiff), |
65 |
|
|
bp::args("self", "data", "x")) |
66 |
|
✗ |
.def("createData", &Model::createData, |
67 |
|
✗ |
bp::with_custodian_and_ward_postcall<0, 2>(), |
68 |
|
|
bp::args("self", "data"), |
69 |
|
|
"Create the CoM position residual data.\n\n" |
70 |
|
|
"Each residual model has its own data that needs to be allocated. " |
71 |
|
|
"This function\n" |
72 |
|
|
"returns the allocated data for a predefined residual.\n" |
73 |
|
|
":param data: shared data\n" |
74 |
|
|
":return residual data.") |
75 |
|
✗ |
.add_property("reference", |
76 |
|
|
bp::make_function(&Model::get_reference, |
77 |
|
✗ |
bp::return_internal_reference<>()), |
78 |
|
|
&Model::set_reference, "reference CoM position"); |
79 |
|
|
} |
80 |
|
|
}; |
81 |
|
|
|
82 |
|
|
template <typename Data> |
83 |
|
|
struct ResidualDataCoMPositionVisitor |
84 |
|
|
: public bp::def_visitor<ResidualDataCoMPositionVisitor<Data>> { |
85 |
|
|
template <class PyClass> |
86 |
|
✗ |
void visit(PyClass& cl) const { |
87 |
|
✗ |
cl.add_property( |
88 |
|
|
"pinocchio", |
89 |
|
✗ |
bp::make_getter(&Data::pinocchio, bp::return_internal_reference<>()), |
90 |
|
|
"pinocchio data"); |
91 |
|
|
} |
92 |
|
|
}; |
93 |
|
|
|
94 |
|
|
#define CROCODDYL_RESIDUAL_MODEL_COM_POSITION_PYTHON_BINDINGS(Scalar) \ |
95 |
|
|
typedef ResidualModelCoMPositionTpl<Scalar> Model; \ |
96 |
|
|
typedef ResidualModelAbstractTpl<Scalar> ModelBase; \ |
97 |
|
|
typedef typename Model::StateMultibody State; \ |
98 |
|
|
typedef typename Model::Vector3s Vector3s; \ |
99 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ |
100 |
|
|
bp::class_<Model, bp::bases<ModelBase>>( \ |
101 |
|
|
"ResidualModelCoMPosition", \ |
102 |
|
|
"This residual function defines the CoM tracking as r = c - cref, with " \ |
103 |
|
|
"c and cref as the current and reference CoM position, respectively.", \ |
104 |
|
|
bp::init<std::shared_ptr<State>, Vector3s, std::size_t>( \ |
105 |
|
|
bp::args("self", "state", "cref", "nu"), \ |
106 |
|
|
"Initialize the CoM position residual model.\n\n" \ |
107 |
|
|
":param state: state of the multibody system\n" \ |
108 |
|
|
":param cref: reference CoM position\n" \ |
109 |
|
|
":param nu: dimension of control vector")) \ |
110 |
|
|
.def(ResidualModelCoMPositionVisitor<Model>()) \ |
111 |
|
|
.def(CastVisitor<Model>()) \ |
112 |
|
|
.def(PrintableVisitor<Model>()) \ |
113 |
|
|
.def(CopyableVisitor<Model>()); |
114 |
|
|
|
115 |
|
|
#define CROCODDYL_RESIDUAL_DATA_COM_POSITION_PYTHON_BINDINGS(Scalar) \ |
116 |
|
|
typedef ResidualDataCoMPositionTpl<Scalar> Data; \ |
117 |
|
|
typedef ResidualDataAbstractTpl<Scalar> DataBase; \ |
118 |
|
|
typedef ResidualModelCoMPositionTpl<Scalar> Model; \ |
119 |
|
|
typedef Model::DataCollectorAbstract DataCollector; \ |
120 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Data>>(); \ |
121 |
|
|
bp::class_<Data, bp::bases<DataBase>>( \ |
122 |
|
|
"ResidualDataCoMPosition", "Data for CoM position residual.\n\n", \ |
123 |
|
|
bp::init<Model*, DataCollector*>( \ |
124 |
|
|
bp::args("self", "model", "data"), \ |
125 |
|
|
"Create CoM position residual data.\n\n" \ |
126 |
|
|
":param model: CoM position residual model\n" \ |
127 |
|
|
":param data: shared data")[bp::with_custodian_and_ward< \ |
128 |
|
|
1, 2, bp::with_custodian_and_ward<1, 3>>()]) \ |
129 |
|
|
.def(ResidualDataCoMPositionVisitor<Data>()) \ |
130 |
|
|
.def(CopyableVisitor<Data>()); |
131 |
|
|
|
132 |
|
✗ |
void exposeResidualCoMPosition() { |
133 |
|
✗ |
CROCODDYL_RESIDUAL_MODEL_COM_POSITION_PYTHON_BINDINGS(double) |
134 |
|
✗ |
CROCODDYL_RESIDUAL_DATA_COM_POSITION_PYTHON_BINDINGS(double) |
135 |
|
|
} |
136 |
|
|
|
137 |
|
|
} // namespace python |
138 |
|
|
} // namespace crocoddyl |
139 |
|
|
|