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