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