Directory: | ./ |
---|---|
File: | bindings/python/crocoddyl/multibody/residuals/contact-control-gravity.cpp |
Date: | 2025-01-16 08:47:40 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 33 | 35 | 94.3% |
Branches: | 26 | 52 | 50.0% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | /////////////////////////////////////////////////////////////////////////////// | ||
2 | // BSD 3-Clause License | ||
3 | // | ||
4 | // Copyright (C) 2020-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-control-gravity.hpp" | ||
11 | |||
12 | #include "python/crocoddyl/multibody/multibody.hpp" | ||
13 | #include "python/crocoddyl/utils/copyable.hpp" | ||
14 | |||
15 | namespace crocoddyl { | ||
16 | namespace python { | ||
17 | |||
18 | 10 | void exposeResidualContactControlGrav() { | |
19 | bp::register_ptr_to_python< | ||
20 | 10 | boost::shared_ptr<ResidualModelContactControlGrav> >(); | |
21 | |||
22 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | bp::class_<ResidualModelContactControlGrav, |
23 | bp::bases<ResidualModelAbstract> >( | ||
24 | "ResidualModelContactControlGrav", | ||
25 | "This residual function defines a residual vector as r = u - g(q,fext),\n" | ||
26 | "with u as the control, q as the position, fext as the external forces " | ||
27 | "and g as the gravity vector in contact", | ||
28 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | bp::init<boost::shared_ptr<StateMultibody>, std::size_t>( |
29 | 20 | bp::args("self", "state", "nu"), | |
30 | "Initialize the contact control-gravity residual model.\n\n" | ||
31 | ":param state: state description\n" | ||
32 | ":param nu: dimension of the control vector")) | ||
33 |
2/4✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
|
10 | .def(bp::init<boost::shared_ptr<StateMultibody> >( |
34 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | bp::args("self", "state"), |
35 | "Initialize the contact control-gravity residual model.\n\n" | ||
36 | "The default nu is obtained from state.nv.\n" | ||
37 | ":param state: state description")) | ||
38 | .def<void (ResidualModelContactControlGrav::*)( | ||
39 | const boost::shared_ptr<ResidualDataAbstract> &, | ||
40 | const Eigen::Ref<const Eigen::VectorXd> &, | ||
41 | 20 | const Eigen::Ref<const Eigen::VectorXd> &)>( | |
42 | "calc", &ResidualModelContactControlGrav::calc, | ||
43 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | bp::args("self", "data", "x", "u"), |
44 | "Compute the contact control-gravity residual.\n\n" | ||
45 | ":param data: residual data\n" | ||
46 | ":param x: state point (dim. state.nx)\n" | ||
47 | ":param u: control input (dim. nu)") | ||
48 | .def<void (ResidualModelContactControlGrav::*)( | ||
49 | const boost::shared_ptr<ResidualDataAbstract> &, | ||
50 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | const Eigen::Ref<const Eigen::VectorXd> &)>( |
51 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | "calc", &ResidualModelAbstract::calc, bp::args("self", "data", "x")) |
52 | .def<void (ResidualModelContactControlGrav::*)( | ||
53 | const boost::shared_ptr<ResidualDataAbstract> &, | ||
54 | const Eigen::Ref<const Eigen::VectorXd> &, | ||
55 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | const Eigen::Ref<const Eigen::VectorXd> &)>( |
56 | "calcDiff", &ResidualModelContactControlGrav::calcDiff, | ||
57 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | bp::args("self", "data", "x", "u"), |
58 | "Compute the Jacobias of the contact control-gravity residual.\n\n" | ||
59 | ":param data: action data\n" | ||
60 | ":param x: state point (dim. state.nx)\n" | ||
61 | ":param u: control input (dim. nu)") | ||
62 | .def<void (ResidualModelContactControlGrav::*)( | ||
63 | const boost::shared_ptr<ResidualDataAbstract> &, | ||
64 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | const Eigen::Ref<const Eigen::VectorXd> &)>( |
65 | "calcDiff", &ResidualModelAbstract::calcDiff, | ||
66 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | bp::args("self", "data", "x")) |
67 |
2/4✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
|
20 | .def("createData", &ResidualModelContactControlGrav::createData, |
68 | ✗ | bp::with_custodian_and_ward_postcall<0, 2>(), | |
69 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | bp::args("self", "data"), |
70 | "Create the contact control-gravity residual data.\n\n" | ||
71 | "Each residual model has its own data that needs to be allocated. " | ||
72 | "This function\n" | ||
73 | "returns the allocated data for a predefined residual.\n" | ||
74 | ":param data: shared data\n" | ||
75 | ":return residual data.") | ||
76 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | .def(CopyableVisitor<ResidualModelContactControlGrav>()); |
77 | |||
78 | bp::register_ptr_to_python< | ||
79 | 10 | boost::shared_ptr<ResidualDataContactControlGrav> >(); | |
80 | |||
81 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | bp::class_<ResidualDataContactControlGrav, bp::bases<ResidualDataAbstract> >( |
82 | "ResidualDataContactControlGrav", | ||
83 | "Data for control gravity residual in contact.\n\n", | ||
84 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | bp::init<ResidualModelContactControlGrav *, DataCollectorAbstract *>( |
85 | 10 | bp::args("self", "model", "data"), | |
86 | "Create contact control-gravity gravity contact residual data.\n\n" | ||
87 | ":param model: control gravity residual model in contact\n" | ||
88 | ✗ | ":param data: shared data")[bp::with_custodian_and_ward< | |
89 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | 1, 2, bp::with_custodian_and_ward<1, 3> >()]) |
90 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | .add_property("pinocchio", |
91 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | bp::make_getter(&ResidualDataContactControlGrav::pinocchio), |
92 | "Pinocchio data used for internal computations") | ||
93 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | .add_property("actuation", |
94 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | bp::make_getter(&ResidualDataContactControlGrav::actuation, |
95 | 10 | bp::return_internal_reference<>()), | |
96 | "actuation model") | ||
97 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | .add_property("fext", |
98 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | bp::make_getter(&ResidualDataContactControlGrav::fext, |
99 | 10 | bp::return_internal_reference<>()), | |
100 | "external spatial forces") | ||
101 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | .def(CopyableVisitor<ResidualDataContactControlGrav>()); |
102 | 10 | } | |
103 | |||
104 | } // namespace python | ||
105 | } // namespace crocoddyl | ||
106 |