1 |
|
|
/////////////////////////////////////////////////////////////////////////////// |
2 |
|
|
// BSD 3-Clause License |
3 |
|
|
// |
4 |
|
|
// Copyright (C) 2020-2023, 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/copyable.hpp" |
13 |
|
|
#include "python/crocoddyl/utils/deprecate.hpp" |
14 |
|
|
|
15 |
|
|
namespace crocoddyl { |
16 |
|
|
namespace python { |
17 |
|
|
|
18 |
|
10 |
void exposeResidualContactWrenchCone() { |
19 |
|
|
bp::register_ptr_to_python< |
20 |
|
10 |
boost::shared_ptr<ResidualModelContactWrenchCone> >(); |
21 |
|
|
|
22 |
✓✗ |
10 |
bp::class_<ResidualModelContactWrenchCone, bp::bases<ResidualModelAbstract> >( |
23 |
|
|
"ResidualModelContactWrenchCone", |
24 |
✓✗ |
10 |
bp::init<boost::shared_ptr<StateMultibody>, pinocchio::FrameIndex, |
25 |
|
|
WrenchCone, std::size_t, bp::optional<bool> >( |
26 |
|
20 |
bp::args("self", "state", "id", "fref", "nu", "fwddyn"), |
27 |
|
|
"Initialize the contact wrench cone residual model.\n\n" |
28 |
|
|
":param state: state of the multibody system\n" |
29 |
|
|
":param id: reference frame id\n" |
30 |
|
|
":param fref: contact wrench cone\n" |
31 |
|
|
":param nu: dimension of control vector\n" |
32 |
|
|
":param fwddyn: indicate if we have a forward dynamics problem " |
33 |
|
|
"(True) or inverse dynamics problem (False) " |
34 |
|
|
"(default True)")) |
35 |
✓✗ |
10 |
.def(bp::init<boost::shared_ptr<StateMultibody>, pinocchio::FrameIndex, |
36 |
|
|
WrenchCone>( |
37 |
✓✗ |
20 |
bp::args("self", "state", "id", "fref"), |
38 |
|
|
"Initialize the contact wrench cone residual model.\n\n" |
39 |
|
|
"The default nu is obtained from state.nv. Note that this " |
40 |
|
|
"constructor can be used for forward-dynamics\n" |
41 |
|
|
"cases only.\n" |
42 |
|
|
":param state: state of the multibody system\n" |
43 |
|
|
":param id: reference frame id\n" |
44 |
✓✗ |
10 |
":param fref: contact wrench cone")) |
45 |
|
|
.def<void (ResidualModelContactWrenchCone::*)( |
46 |
|
|
const boost::shared_ptr<ResidualDataAbstract>&, |
47 |
|
|
const Eigen::Ref<const Eigen::VectorXd>&, |
48 |
|
|
const Eigen::Ref<const Eigen::VectorXd>&)>( |
49 |
|
|
"calc", &ResidualModelContactWrenchCone::calc, |
50 |
✓✗ |
20 |
bp::args("self", "data", "x", "u"), |
51 |
|
|
"Compute the contact wrench cone residual.\n\n" |
52 |
|
|
":param data: residual data\n" |
53 |
|
|
":param x: state point (dim. state.nx)\n" |
54 |
|
20 |
":param u: control input (dim. nu)") |
55 |
|
|
.def<void (ResidualModelContactWrenchCone::*)( |
56 |
|
|
const boost::shared_ptr<ResidualDataAbstract>&, |
57 |
|
|
const Eigen::Ref<const Eigen::VectorXd>&)>( |
58 |
✓✗✓✗
|
20 |
"calc", &ResidualModelAbstract::calc, bp::args("self", "data", "x")) |
59 |
|
|
.def<void (ResidualModelContactWrenchCone::*)( |
60 |
|
|
const boost::shared_ptr<ResidualDataAbstract>&, |
61 |
|
|
const Eigen::Ref<const Eigen::VectorXd>&, |
62 |
|
|
const Eigen::Ref<const Eigen::VectorXd>&)>( |
63 |
|
|
"calcDiff", &ResidualModelContactWrenchCone::calcDiff, |
64 |
✓✗ |
20 |
bp::args("self", "data", "x", "u"), |
65 |
|
|
"Compute the Jacobians of the contact wrench cone residual.\n\n" |
66 |
|
|
"It assumes that calc has been run first.\n" |
67 |
|
|
":param data: action data\n" |
68 |
|
|
":param x: state point (dim. state.nx)\n" |
69 |
✓✗ |
10 |
":param u: control input (dim. nu)") |
70 |
|
|
.def<void (ResidualModelContactWrenchCone::*)( |
71 |
|
|
const boost::shared_ptr<ResidualDataAbstract>&, |
72 |
|
|
const Eigen::Ref<const Eigen::VectorXd>&)>( |
73 |
|
|
"calcDiff", &ResidualModelAbstract::calcDiff, |
74 |
✓✗✓✗
|
20 |
bp::args("self", "data", "x")) |
75 |
|
|
.def("createData", &ResidualModelContactWrenchCone::createData, |
76 |
|
|
bp::with_custodian_and_ward_postcall<0, 2>(), |
77 |
✓✗ |
20 |
bp::args("self", "data"), |
78 |
|
|
"Create the contact wrench cone residual data.\n\n" |
79 |
|
|
"Each residual model has its own data that needs to be allocated. " |
80 |
|
|
"This function\n" |
81 |
|
|
"returns the allocated data for the contact wrench cone residual.\n" |
82 |
|
|
":param data: shared data\n" |
83 |
✓✗✓✗
|
20 |
":return residual data.") |
84 |
|
|
.add_property( |
85 |
✓✗ |
10 |
"id", bp::make_function(&ResidualModelContactWrenchCone::get_id), |
86 |
✓✗ |
20 |
bp::make_function( |
87 |
|
|
&ResidualModelContactWrenchCone::set_id, |
88 |
✓✗✓✗
|
20 |
deprecated<>( |
89 |
|
|
"Deprecated. Do not use set_id, instead create a new model")), |
90 |
✓✗ |
10 |
"reference frame id") |
91 |
|
|
.add_property( |
92 |
|
|
"reference", |
93 |
|
|
bp::make_function(&ResidualModelContactWrenchCone::get_reference, |
94 |
|
10 |
bp::return_internal_reference<>()), |
95 |
|
|
&ResidualModelContactWrenchCone::set_reference, |
96 |
✓✗✓✗
|
10 |
"reference contact wrench cone") |
97 |
✓✗ |
10 |
.def(CopyableVisitor<ResidualModelContactWrenchCone>()); |
98 |
|
|
|
99 |
|
|
bp::register_ptr_to_python< |
100 |
|
10 |
boost::shared_ptr<ResidualDataContactWrenchCone> >(); |
101 |
|
|
|
102 |
✓✗ |
10 |
bp::class_<ResidualDataContactWrenchCone, bp::bases<ResidualDataAbstract> >( |
103 |
|
|
"ResidualDataContactWrenchCone", |
104 |
|
|
"Data for contact wrench cone residual.\n\n", |
105 |
✓✗ |
10 |
bp::init<ResidualModelContactWrenchCone*, DataCollectorAbstract*>( |
106 |
✓✗ |
10 |
bp::args("self", "model", "data"), |
107 |
|
|
"Create contact wrench cone residual data.\n\n" |
108 |
|
|
":param model: contact wrench cone residual model\n" |
109 |
|
10 |
":param data: shared data")[bp::with_custodian_and_ward< |
110 |
✓✗ |
20 |
1, 2, bp::with_custodian_and_ward<1, 3> >()]) |
111 |
|
|
.add_property( |
112 |
|
|
"contact", |
113 |
✓✗ |
10 |
bp::make_getter(&ResidualDataContactWrenchCone::contact, |
114 |
|
|
bp::return_value_policy<bp::return_by_value>()), |
115 |
✓✗ |
20 |
bp::make_setter(&ResidualDataContactWrenchCone::contact), |
116 |
✓✗ |
10 |
"contact data associated with the current residual") |
117 |
✓✗ |
10 |
.def(CopyableVisitor<ResidualDataContactWrenchCone>()); |
118 |
|
10 |
} |
119 |
|
|
|
120 |
|
|
} // namespace python |
121 |
|
|
} // namespace crocoddyl |