Directory: | ./ |
---|---|
File: | bindings/python/crocoddyl/core/residuals/joint-acceleration.cpp |
Date: | 2025-02-24 23:41:29 |
Exec | Total | Coverage | |
---|---|---|---|
Lines: | 26 | 27 | 96.3% |
Branches: | 24 | 48 | 50.0% |
Line | Branch | Exec | Source |
---|---|---|---|
1 | /////////////////////////////////////////////////////////////////////////////// | ||
2 | // BSD 3-Clause License | ||
3 | // | ||
4 | // Copyright (C) 2022-2023, Heriot-Watt University | ||
5 | // Copyright note valid unless otherwise stated in individual files. | ||
6 | // All rights reserved. | ||
7 | /////////////////////////////////////////////////////////////////////////////// | ||
8 | |||
9 | #include "crocoddyl/core/residuals/joint-acceleration.hpp" | ||
10 | |||
11 | #include "python/crocoddyl/core/core.hpp" | ||
12 | #include "python/crocoddyl/utils/copyable.hpp" | ||
13 | |||
14 | namespace crocoddyl { | ||
15 | namespace python { | ||
16 | |||
17 | 10 | void exposeResidualJointAcceleration() { | |
18 | 10 | bp::register_ptr_to_python<std::shared_ptr<ResidualModelJointAcceleration>>(); | |
19 | |||
20 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | bp::class_<ResidualModelJointAcceleration, bp::bases<ResidualModelAbstract>>( |
21 | "ResidualModelJointAcceleration", | ||
22 | "This residual function defines a residual vector as r = a - aref, with " | ||
23 | "a and aref as the current and\n" | ||
24 | "reference joint acceleration (i.e., generalized acceleration), " | ||
25 | "respectively.", | ||
26 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | bp::init<std::shared_ptr<StateAbstract>, Eigen::VectorXd, std::size_t>( |
27 | 20 | bp::args("self", "state", "aref", "nu"), | |
28 | "Initialize the joint-acceleration residual model.\n\n" | ||
29 | ":param state: state description\n" | ||
30 | ":param aref: reference joint acceleration\n" | ||
31 | ":param nu: dimension of the control vector")) | ||
32 |
2/4✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
|
10 | .def(bp::init<std::shared_ptr<StateAbstract>, Eigen::VectorXd>( |
33 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | bp::args("self", "state", "aref"), |
34 | "Initialize the joint-acceleration residual model.\n\n" | ||
35 | "The default nu value is obtained from state.nv.\n" | ||
36 | ":param state: state description\n" | ||
37 | ":param aref: reference joint acceleration")) | ||
38 |
2/4✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
|
10 | .def(bp::init<std::shared_ptr<StateAbstract>, std::size_t>( |
39 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | bp::args("self", "state", "nu"), |
40 | "Initialize the joint-acceleration residual model.\n\n" | ||
41 | "The default reference joint-acceleration is obtained from " | ||
42 | "np.zero(actuation.nu).\n" | ||
43 | ":param state: state description\n" | ||
44 | ":param nu: dimension of the control vector")) | ||
45 |
2/4✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
|
10 | .def(bp::init<std::shared_ptr<StateAbstract>>( |
46 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | bp::args("self", "state"), |
47 | "Initialize the joint-acceleration residual model.\n\n" | ||
48 | "The default reference joint-acceleration is obtained from " | ||
49 | "np.zero(actuation.nu).\n" | ||
50 | "The default nu value is obtained from state.nv.\n" | ||
51 | ":param state: state description")) | ||
52 | .def<void (ResidualModelJointAcceleration::*)( | ||
53 | const std::shared_ptr<ResidualDataAbstract>&, | ||
54 | const Eigen::Ref<const Eigen::VectorXd>&, | ||
55 | 20 | const Eigen::Ref<const Eigen::VectorXd>&)>( | |
56 | "calc", &ResidualModelJointAcceleration::calc, | ||
57 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | bp::args("self", "data", "x", "u"), |
58 | "Compute the joint-acceleration residual.\n\n" | ||
59 | ":param data: residual data\n" | ||
60 | ":param x: state point (dim. state.nx)\n" | ||
61 | ":param u: control input (dim. nu)") | ||
62 | .def<void (ResidualModelJointAcceleration::*)( | ||
63 | const std::shared_ptr<ResidualDataAbstract>&, | ||
64 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | const Eigen::Ref<const Eigen::VectorXd>&)>( |
65 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | "calc", &ResidualModelAbstract::calc, bp::args("self", "data", "x")) |
66 | .def<void (ResidualModelJointAcceleration::*)( | ||
67 | const std::shared_ptr<ResidualDataAbstract>&, | ||
68 | const Eigen::Ref<const Eigen::VectorXd>&, | ||
69 |
2/4✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
|
20 | const Eigen::Ref<const Eigen::VectorXd>&)>( |
70 | "calcDiff", &ResidualModelJointAcceleration::calcDiff, | ||
71 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | bp::args("self", "data", "x", "u"), |
72 | "Compute the Jacobians of the joint-acceleration residual.\n\n" | ||
73 | "It assumes that calc has been run first.\n" | ||
74 | ":param data: residual data\n" | ||
75 | ":param x: state point (dim. state.nx)\n" | ||
76 | ":param u: control input (dim. nu)") | ||
77 | .def<void (ResidualModelJointAcceleration::*)( | ||
78 | const std::shared_ptr<ResidualDataAbstract>&, | ||
79 | 20 | const Eigen::Ref<const Eigen::VectorXd>&)>( | |
80 | "calcDiff", &ResidualModelAbstract::calcDiff, | ||
81 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | bp::args("self", "data", "x")) |
82 |
2/4✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 10 times.
✗ Branch 5 not taken.
|
20 | .def("createData", &ResidualModelJointAcceleration::createData, |
83 | ✗ | bp::with_custodian_and_ward_postcall<0, 2>(), | |
84 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
20 | bp::args("self", "data"), |
85 | "Create the joint-acceleration 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 joint-acceleration residual.\n" | ||
89 | ":param data: shared data\n" | ||
90 | ":return residual data.") | ||
91 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | .add_property( |
92 | "reference", | ||
93 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | bp::make_function(&ResidualModelJointAcceleration::get_reference, |
94 | 10 | bp::return_internal_reference<>()), | |
95 | &ResidualModelJointAcceleration::set_reference, | ||
96 | "reference joint acceleration") | ||
97 |
1/2✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
|
10 | .def(CopyableVisitor<ResidualModelJointAcceleration>()); |
98 | 10 | } | |
99 | |||
100 | } // namespace python | ||
101 | } // namespace crocoddyl | ||
102 |