GCC Code Coverage Report


Directory: ./
File: bindings/python/crocoddyl/core/residuals/joint-acceleration.cpp
Date: 2025-01-16 08:47:40
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 bp::register_ptr_to_python<
19 10 boost::shared_ptr<ResidualModelJointAcceleration>>();
20
21
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::class_<ResidualModelJointAcceleration, bp::bases<ResidualModelAbstract>>(
22 "ResidualModelJointAcceleration",
23 "This residual function defines a residual vector as r = a - aref, with "
24 "a and aref as the current and\n"
25 "reference joint acceleration (i.e., generalized acceleration), "
26 "respectively.",
27
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::init<boost::shared_ptr<StateAbstract>, Eigen::VectorXd, std::size_t>(
28 20 bp::args("self", "state", "aref", "nu"),
29 "Initialize the joint-acceleration residual model.\n\n"
30 ":param state: state description\n"
31 ":param aref: reference joint acceleration\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<StateAbstract>, Eigen::VectorXd>(
34
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::args("self", "state", "aref"),
35 "Initialize the joint-acceleration residual model.\n\n"
36 "The default nu value is obtained from state.nv.\n"
37 ":param state: state description\n"
38 ":param aref: reference joint acceleration"))
39
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<StateAbstract>, std::size_t>(
40
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::args("self", "state", "nu"),
41 "Initialize the joint-acceleration residual model.\n\n"
42 "The default reference joint-acceleration is obtained from "
43 "np.zero(actuation.nu).\n"
44 ":param state: state description\n"
45 ":param nu: dimension of the control vector"))
46
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<StateAbstract>>(
47
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::args("self", "state"),
48 "Initialize the joint-acceleration residual model.\n\n"
49 "The default reference joint-acceleration is obtained from "
50 "np.zero(actuation.nu).\n"
51 "The default nu value is obtained from state.nv.\n"
52 ":param state: state description"))
53 .def<void (ResidualModelJointAcceleration::*)(
54 const boost::shared_ptr<ResidualDataAbstract>&,
55 const Eigen::Ref<const Eigen::VectorXd>&,
56 20 const Eigen::Ref<const Eigen::VectorXd>&)>(
57 "calc", &ResidualModelJointAcceleration::calc,
58
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::args("self", "data", "x", "u"),
59 "Compute the joint-acceleration residual.\n\n"
60 ":param data: residual data\n"
61 ":param x: state point (dim. state.nx)\n"
62 ":param u: control input (dim. nu)")
63 .def<void (ResidualModelJointAcceleration::*)(
64 const boost::shared_ptr<ResidualDataAbstract>&,
65
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 const Eigen::Ref<const Eigen::VectorXd>&)>(
66
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 "calc", &ResidualModelAbstract::calc, bp::args("self", "data", "x"))
67 .def<void (ResidualModelJointAcceleration::*)(
68 const boost::shared_ptr<ResidualDataAbstract>&,
69 const Eigen::Ref<const Eigen::VectorXd>&,
70
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>&)>(
71 "calcDiff", &ResidualModelJointAcceleration::calcDiff,
72
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::args("self", "data", "x", "u"),
73 "Compute the Jacobians of the joint-acceleration residual.\n\n"
74 "It assumes that calc has been run first.\n"
75 ":param data: residual data\n"
76 ":param x: state point (dim. state.nx)\n"
77 ":param u: control input (dim. nu)")
78 .def<void (ResidualModelJointAcceleration::*)(
79 const boost::shared_ptr<ResidualDataAbstract>&,
80 20 const Eigen::Ref<const Eigen::VectorXd>&)>(
81 "calcDiff", &ResidualModelAbstract::calcDiff,
82
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::args("self", "data", "x"))
83
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,
84 bp::with_custodian_and_ward_postcall<0, 2>(),
85
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::args("self", "data"),
86 "Create the joint-acceleration residual data.\n\n"
87 "Each residual model has its own data that needs to be allocated. "
88 "This function\n"
89 "returns the allocated data for the joint-acceleration residual.\n"
90 ":param data: shared data\n"
91 ":return residual data.")
92
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property(
93 "reference",
94
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_function(&ResidualModelJointAcceleration::get_reference,
95 10 bp::return_internal_reference<>()),
96 &ResidualModelJointAcceleration::set_reference,
97 "reference joint acceleration")
98
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .def(CopyableVisitor<ResidualModelJointAcceleration>());
99 10 }
100
101 } // namespace python
102 } // namespace crocoddyl
103