GCC Code Coverage Report


Directory: ./
File: bindings/python/crocoddyl/multibody/residuals/contact-force.cpp
Date: 2025-01-16 08:47:40
Exec Total Coverage
Lines: 35 38 92.1%
Branches: 30 60 50.0%

Line Branch Exec Source
1 ///////////////////////////////////////////////////////////////////////////////
2 // BSD 3-Clause License
3 //
4 // Copyright (C) 2019-2025, 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
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
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
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
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
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,
41 pinocchio::Force, std::size_t>(
42
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
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 "coordinates\n"))
52 .def<void (ResidualModelContactForce::*)(
53 const boost::shared_ptr<ResidualDataAbstract>&,
54 const Eigen::Ref<const Eigen::VectorXd>&,
55 20 const Eigen::Ref<const Eigen::VectorXd>&)>(
56 "calc", &ResidualModelContactForce::calc,
57
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
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 ":param u: control input (dim. nu)")
62 .def<void (ResidualModelContactForce::*)(
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
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
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
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 const Eigen::Ref<const Eigen::VectorXd>&)>(
70 "calcDiff", &ResidualModelContactForce::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 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 ":param u: control input (dim. nu)")
77 .def<void (ResidualModelContactForce::*)(
78 const boost::shared_ptr<ResidualDataAbstract>&,
79
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 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", &ResidualModelContactForce::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 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 ":return residual data.")
91
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property(
92
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 "id", bp::make_function(&ResidualModelContactForce::get_id),
93
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::make_function(
94 &ResidualModelContactForce::set_id,
95
2/4
✓ Branch 2 taken 10 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 10 times.
✗ Branch 6 not taken.
20 deprecated<>(
96 "Deprecated. Do not use set_id, instead create a new model")),
97 "reference frame id")
98
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property("reference",
99
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_function(
100 &ResidualModelContactForce::get_reference,
101 10 bp::return_value_policy<bp::copy_const_reference>()),
102 &ResidualModelContactForce::set_reference,
103 "reference spatial force")
104
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .def(CopyableVisitor<ResidualModelContactForce>());
105
106 10 bp::register_ptr_to_python<boost::shared_ptr<ResidualDataContactForce> >();
107
108
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::class_<ResidualDataContactForce, bp::bases<ResidualDataAbstract> >(
109 "ResidualDataContactForce", "Data for contact force residual.\n\n",
110
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::init<ResidualModelContactForce*, DataCollectorAbstract*>(
111 10 bp::args("self", "model", "data"),
112 "Create contact force residual data.\n\n"
113 ":param model: contact force residual model\n"
114 ":param data: shared data")[bp::with_custodian_and_ward<
115
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 1, 2, bp::with_custodian_and_ward<1, 3> >()])
116
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .add_property(
117 "contact",
118
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 bp::make_getter(&ResidualDataContactForce::contact,
119 bp::return_value_policy<bp::return_by_value>()),
120
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
20 bp::make_setter(&ResidualDataContactForce::contact),
121 "contact data associated with the current residual")
122
1/2
✓ Branch 1 taken 10 times.
✗ Branch 2 not taken.
10 .def(CopyableVisitor<ResidualDataContactForce>());
123 10 }
124
125 } // namespace python
126 } // namespace crocoddyl
127