Line |
Branch |
Exec |
Source |
1 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
2 |
|
|
// BSD 3-Clause License |
3 |
|
|
// |
4 |
|
|
// Copyright (C) 2019-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 float |
10 |
|
|
#include "crocoddyl/multibody/residuals/contact-friction-cone.hpp" |
11 |
|
|
|
12 |
|
|
#include "python/crocoddyl/multibody/multibody.hpp" |
13 |
|
|
#include "python/crocoddyl/utils/deprecate.hpp" |
14 |
|
|
|
15 |
|
|
namespace crocoddyl { |
16 |
|
|
namespace python { |
17 |
|
|
|
18 |
|
|
template <typename Model> |
19 |
|
|
struct ResidualModelContactFrictionConeVisitor |
20 |
|
|
: public bp::def_visitor<ResidualModelContactFrictionConeVisitor<Model>> { |
21 |
|
|
typedef typename Model::ResidualDataAbstract Data; |
22 |
|
|
typedef typename Model::StateMultibody State; |
23 |
|
|
typedef typename Model::FrictionCone Cone; |
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, Cone>( |
28 |
|
|
bp::args("self", "state", "id", "fref"), |
29 |
|
|
"Initialize the contact friction cone residual model.\n\n" |
30 |
|
|
"The default nu is obtained from state.nv. Note that this " |
31 |
|
|
"constructor can be used for forward-dynamics\n" |
32 |
|
|
"cases only.\n" |
33 |
|
|
":param state: state of the multibody system\n" |
34 |
|
|
":param id: reference frame id\n" |
35 |
|
|
":param fref: frame friction cone")) |
36 |
|
✗ |
.def( |
37 |
|
|
"calc", |
38 |
|
|
static_cast<void (Model::*)( |
39 |
|
|
const std::shared_ptr<Data>&, const Eigen::Ref<const VectorXs>&, |
40 |
|
|
const Eigen::Ref<const VectorXs>&)>(&Model::calc), |
41 |
|
|
"Compute the contact friction cone residual.\n\n" |
42 |
|
|
":param data: residual data\n" |
43 |
|
|
":param x: state point (dim. state.nx)\n" |
44 |
|
|
":param u: control input (dim. nu)") |
45 |
|
✗ |
.def("calc", |
46 |
|
|
static_cast<void (Model::*)(const std::shared_ptr<Data>&, |
47 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
48 |
|
|
&Model::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 contact friction cone 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("calcDiff", |
62 |
|
|
static_cast<void (Model::*)(const std::shared_ptr<Data>&, |
63 |
|
|
const Eigen::Ref<const VectorXs>&)>( |
64 |
|
|
&Model::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 contact friction cone 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 the contact friction cone " |
73 |
|
|
"residual.\n" |
74 |
|
|
":param data: shared data\n" |
75 |
|
|
":return residual data.") |
76 |
|
✗ |
.add_property( |
77 |
|
|
"id", bp::make_function(&Model::get_id), |
78 |
|
|
bp::make_function(&Model::set_id, |
79 |
|
✗ |
deprecated<>("Deprecated. Do not use set_id, " |
80 |
|
|
"instead create a new model")), |
81 |
|
|
"reference frame id") |
82 |
|
✗ |
.add_property("reference", |
83 |
|
|
bp::make_function(&Model::get_reference, |
84 |
|
✗ |
bp::return_internal_reference<>()), |
85 |
|
|
&Model::set_reference, "reference contact friction cone"); |
86 |
|
|
} |
87 |
|
|
}; |
88 |
|
|
|
89 |
|
|
template <typename Data> |
90 |
|
|
struct ResidualDataContactFrictionConeVisitor |
91 |
|
|
: public bp::def_visitor<ResidualDataContactFrictionConeVisitor<Data>> { |
92 |
|
|
template <class PyClass> |
93 |
|
✗ |
void visit(PyClass& cl) const { |
94 |
|
✗ |
cl.add_property( |
95 |
|
|
"contact", |
96 |
|
|
bp::make_getter(&Data::contact, |
97 |
|
✗ |
bp::return_value_policy<bp::return_by_value>()), |
98 |
|
|
bp::make_setter(&Data::contact), |
99 |
|
|
"contact data associated with the current residual"); |
100 |
|
|
} |
101 |
|
|
}; |
102 |
|
|
|
103 |
|
|
#define CROCODDYL_RESIDUAL_MODEL_CONTACT_FRICTION_CONE_PYTHON_BINDINGS(Scalar) \ |
104 |
|
|
typedef ResidualModelContactFrictionConeTpl<Scalar> Model; \ |
105 |
|
|
typedef ResidualModelAbstractTpl<Scalar> ModelBase; \ |
106 |
|
|
typedef typename Model::StateMultibody State; \ |
107 |
|
|
typedef typename Model::FrictionCone Cone; \ |
108 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Model>>(); \ |
109 |
|
|
bp::class_<Model, bp::bases<ModelBase>>( \ |
110 |
|
|
"ResidualModelContactFrictionCone", \ |
111 |
|
|
"This residual function is defined as r = A*f, where A, f describe the " \ |
112 |
|
|
"linearized friction cone and the spatial force, respectively.", \ |
113 |
|
|
bp::init<std::shared_ptr<State>, pinocchio::FrameIndex, Cone, \ |
114 |
|
|
std::size_t, bp::optional<bool>>( \ |
115 |
|
|
bp::args("self", "state", "id", "fref", "nu", "fwddyn"), \ |
116 |
|
|
"Initialize the contact friction cone residual model.\n\n" \ |
117 |
|
|
":param state: state of the multibody system\n" \ |
118 |
|
|
":param id: reference frame id\n" \ |
119 |
|
|
":param fref: frame friction cone\n" \ |
120 |
|
|
":param nu: dimension of control vector\n" \ |
121 |
|
|
":param fwddyn: indicate if we have a forward dynamics problem " \ |
122 |
|
|
"(True) or inverse dynamics problem (False) (default True)")) \ |
123 |
|
|
.def(ResidualModelContactFrictionConeVisitor<Model>()) \ |
124 |
|
|
.def(CastVisitor<Model>()) \ |
125 |
|
|
.def(PrintableVisitor<Model>()) \ |
126 |
|
|
.def(CopyableVisitor<Model>()); |
127 |
|
|
|
128 |
|
|
#define CROCODDYL_RESIDUAL_DATA_CONTACT_FRICTION_CONE_PYTHON_BINDINGS(Scalar) \ |
129 |
|
|
typedef ResidualDataContactFrictionConeTpl<Scalar> Data; \ |
130 |
|
|
typedef ResidualDataAbstractTpl<Scalar> DataBase; \ |
131 |
|
|
typedef ResidualModelContactFrictionConeTpl<Scalar> Model; \ |
132 |
|
|
typedef Model::DataCollectorAbstract DataCollector; \ |
133 |
|
|
bp::register_ptr_to_python<std::shared_ptr<Data>>(); \ |
134 |
|
|
bp::class_<Data, bp::bases<DataBase>>( \ |
135 |
|
|
"ResidualDataContactFrictionCone", \ |
136 |
|
|
"Data for contact friction cone residual.\n\n", \ |
137 |
|
|
bp::init<Model*, DataCollector*>( \ |
138 |
|
|
bp::args("self", "model", "data"), \ |
139 |
|
|
"Create contact friction cone residual data.\n\n" \ |
140 |
|
|
":param model: contact friction cone residual model\n" \ |
141 |
|
|
":param data: shared data")[bp::with_custodian_and_ward< \ |
142 |
|
|
1, 2, bp::with_custodian_and_ward<1, 3>>()]) \ |
143 |
|
|
.def(ResidualDataContactFrictionConeVisitor<Data>()) \ |
144 |
|
|
.def(CopyableVisitor<Data>()); |
145 |
|
|
|
146 |
|
✗ |
void exposeResidualContactFrictionCone() { |
147 |
|
✗ |
CROCODDYL_RESIDUAL_MODEL_CONTACT_FRICTION_CONE_PYTHON_BINDINGS(float) |
148 |
|
✗ |
CROCODDYL_RESIDUAL_DATA_CONTACT_FRICTION_CONE_PYTHON_BINDINGS(float) |
149 |
|
|
} |
150 |
|
|
|
151 |
|
|
} // namespace python |
152 |
|
|
} // namespace crocoddyl |
153 |
|
|
|