GCC Code Coverage Report


Directory: ./
File: bindings/python/crocoddyl/multibody/residuals/contact-cop-position.cpp
Date: 2025-01-16 08:47:40
Exec Total Coverage
Lines: 34 37 91.9%
Branches: 28 56 50.0%

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