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/frame-placement.hpp" |
11 |
|
|
|
12 |
|
|
#include "python/crocoddyl/multibody/multibody.hpp" |
13 |
|
|
|
14 |
|
|
namespace crocoddyl { |
15 |
|
|
namespace python { |
16 |
|
|
|
17 |
|
|
template <typename Model> |
18 |
|
|
struct ResidualModelFramePlacementVisitor |
19 |
|
|
: public bp::def_visitor<ResidualModelFramePlacementVisitor<Model>> { |
20 |
|
|
typedef typename Model::ResidualDataAbstract Data; |
21 |
|
|
typedef typename Model::Base ModelBase; |
22 |
|
|
typedef typename Model::StateMultibody State; |
23 |
|
|
typedef typename Model::SE3 SE3; |
24 |
|
|
typedef typename Model::VectorXs VectorXs; |
25 |
|
|
template <class PyClass> |
26 |
|
✗ |
void visit(PyClass& cl) const { |
27 |
|
✗ |
cl.def(bp::init<std::shared_ptr<State>, pinocchio::FrameIndex, SE3>( |
28 |
|
|
bp::args("self", "state", "id", "pref"), |
29 |
|
|
"Initialize the frame placement residual model.\n\n" |
30 |
|
|
"The default nu value is obtained from state.nv.\n" |
31 |
|
|
":param state: state of the multibody system\n" |
32 |
|
|
":param id: reference frame id\n" |
33 |
|
|
":param pref: reference frame placement")) |
34 |
|
✗ |
.def( |
35 |
|
|
"calc", |
36 |
|
|
static_cast<void (Model::*)( |
37 |
|
|
const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, |
38 |
|
|
const Eigen::Ref<const VectorXs>&)>(&Model::calc), |
39 |
|
|
bp::args("self", "data", "x", "u"), |
40 |
|
|
"Compute the frame placement residual.\n\n" |
41 |
|
|
":param data: residual data\n" |
42 |
|
|
":param x: state point (dim. state.nx)\n" |
43 |
|
|
":param u: control input (dim. nu)") |
44 |
|
✗ |
.def( |
45 |
|
|
"calc", |
46 |
|
|
static_cast<void (ModelBase::*)(const std::shared_ptr<Data>&, |
47 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
48 |
|
|
&ModelBase::calc), |
49 |
|
|
bp::args("self", "data", "x")) |
50 |
|
✗ |
.def( |
51 |
|
|
"calcDiff", |
52 |
|
|
static_cast<void (Model::*)( |
53 |
|
|
const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, |
54 |
|
|
const Eigen::Ref<const VectorXs>&)>(&Model::calcDiff), |
55 |
|
|
bp::args("self", "data", "x", "u"), |
56 |
|
|
"Compute the Jacobians of the frame placement residual.\n\n" |
57 |
|
|
"It assumes that calc has been run first.\n" |
58 |
|
|
":param data: action data\n" |
59 |
|
|
":param x: state point (dim. state.nx)\n" |
60 |
|
|
":param u: control input (dim. nu)") |
61 |
|
✗ |
.def( |
62 |
|
|
"calcDiff", |
63 |
|
|
static_cast<void (ModelBase::*)(const std::shared_ptr<Data>&, |
64 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
65 |
|
|
&ModelBase::calcDiff), |
66 |
|
|
bp::args("self", "data", "x")) |
67 |
|
✗ |
.def("createData", &ResidualModelFramePlacement::createData, |
68 |
|
✗ |
bp::with_custodian_and_ward_postcall<0, 2>(), |
69 |
|
|
bp::args("self", "data"), |
70 |
|
|
"Create the frame placement residual data.\n\n" |
71 |
|
|
"Each residual model has its own data that needs to be allocated. " |
72 |
|
|
"This function returns the allocated data for the frame placement " |
73 |
|
|
"residual.\n" |
74 |
|
|
":param data: shared data\n" |
75 |
|
|
":return residual data.") |
76 |
|
✗ |
.add_property("id", &Model::get_id, &Model::set_id, |
77 |
|
|
"reference frame id") |
78 |
|
✗ |
.add_property("reference", |
79 |
|
|
bp::make_function( |
80 |
|
|
&Model::get_reference, |
81 |
|
✗ |
bp::return_value_policy<bp::copy_const_reference>()), |
82 |
|
|
&Model::set_reference, "reference frame placement"); |
83 |
|
|
} |
84 |
|
|
}; |
85 |
|
|
|
86 |
|
|
template <typename Data> |
87 |
|
|
struct ResidualDataFramePlacementVisitor |
88 |
|
|
: public bp::def_visitor<ResidualDataFramePlacementVisitor<Data>> { |
89 |
|
|
template <class PyClass> |
90 |
|
✗ |
void visit(PyClass& cl) const { |
91 |
|
✗ |
cl.add_property( |
92 |
|
|
"pinocchio", |
93 |
|
✗ |
bp::make_getter(&Data::pinocchio, bp::return_internal_reference<>()), |
94 |
|
|
"pinocchio data") |
95 |
|
✗ |
.add_property( |
96 |
|
|
"rMf", |
97 |
|
|
bp::make_getter(&Data::rMf, |
98 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
99 |
|
|
"error frame placement of the frame") |
100 |
|
✗ |
.add_property( |
101 |
|
|
"rJf", |
102 |
|
✗ |
bp::make_getter(&Data::rJf, bp::return_internal_reference<>()), |
103 |
|
|
"error Jacobian of the frame") |
104 |
|
✗ |
.add_property( |
105 |
|
|
"fJf", |
106 |
|
✗ |
bp::make_getter(&Data::fJf, bp::return_internal_reference<>()), |
107 |
|
|
"local Jacobian of the frame"); |
108 |
|
|
} |
109 |
|
|
}; |
110 |
|
|
|
111 |
|
|
#define CROCODDYL_RESIDUAL_MODEL_FRAME_PLACEMENT_PYTHON_BINDINGS(Scalar) \ |
112 |
|
|
typedef ResidualModelFramePlacementTpl<Scalar> Model; \ |
113 |
|
|
typedef ResidualModelAbstractTpl<Scalar> ModelBase; \ |
114 |
|
|
typedef typename Model::StateMultibody State; \ |
115 |
|
|
typedef typename Model::SE3 SE3; \ |
116 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ |
117 |
|
|
bp::class_<Model, bp::bases<ModelBase>>( \ |
118 |
|
|
"ResidualModelFramePlacement", \ |
119 |
|
|
"This residual function defines the tracking of theframe placement " \ |
120 |
|
|
"residual as r = p - pref, with p and pref as the current and " \ |
121 |
|
|
"reference frame placements, respectively.", \ |
122 |
|
|
bp::init<std::shared_ptr<State>, pinocchio::FrameIndex, SE3, \ |
123 |
|
|
std::size_t>( \ |
124 |
|
|
bp::args("self", "state", "id", "pref", "nu"), \ |
125 |
|
|
"Initialize the frame placement residual model.\n\n" \ |
126 |
|
|
":param state: state of the multibody system\n" \ |
127 |
|
|
":param id: reference frame id\n" \ |
128 |
|
|
":param pref: reference frame placement\n" \ |
129 |
|
|
":param nu: dimension of control vector")) \ |
130 |
|
|
.def(ResidualModelFramePlacementVisitor<Model>()) \ |
131 |
|
|
.def(CastVisitor<Model>()) \ |
132 |
|
|
.def(PrintableVisitor<Model>()) \ |
133 |
|
|
.def(CopyableVisitor<Model>()); |
134 |
|
|
|
135 |
|
|
#define CROCODDYL_RESIDUAL_DATA_FRAME_PLACEMENT_PYTHON_BINDINGS(Scalar) \ |
136 |
|
|
typedef ResidualDataFramePlacementTpl<Scalar> Data; \ |
137 |
|
|
typedef ResidualDataAbstractTpl<Scalar> DataBase; \ |
138 |
|
|
typedef ResidualModelFramePlacementTpl<Scalar> Model; \ |
139 |
|
|
typedef Model::DataCollectorAbstract DataCollector; \ |
140 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Data>>(); \ |
141 |
|
|
bp::class_<Data, bp::bases<DataBase>>( \ |
142 |
|
|
"ResidualDataFramePlacement", "Data for frame placement residual.\n\n", \ |
143 |
|
|
bp::init<Model*, DataCollector*>( \ |
144 |
|
|
bp::args("self", "model", "data"), \ |
145 |
|
|
"Create frame placement residual data.\n\n" \ |
146 |
|
|
":param model: frame placement residual model\n" \ |
147 |
|
|
":param data: shared data")[bp::with_custodian_and_ward< \ |
148 |
|
|
1, 2, bp::with_custodian_and_ward<1, 3>>()]) \ |
149 |
|
|
.def(ResidualDataFramePlacementVisitor<Data>()) \ |
150 |
|
|
.def(CopyableVisitor<Data>()); |
151 |
|
|
|
152 |
|
✗ |
void exposeResidualFramePlacement() { |
153 |
|
✗ |
CROCODDYL_RESIDUAL_MODEL_FRAME_PLACEMENT_PYTHON_BINDINGS(double) |
154 |
|
✗ |
CROCODDYL_RESIDUAL_DATA_FRAME_PLACEMENT_PYTHON_BINDINGS(double) |
155 |
|
|
} |
156 |
|
|
|
157 |
|
|
} // namespace python |
158 |
|
|
} // namespace crocoddyl |
159 |
|
|
|