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