GCC Code Coverage Report


Directory: ./
File: include/tsid/bindings/python/contacts/measured-6d-wrench.hpp
Date: 2025-03-29 14:29:37
Exec Total Coverage
Lines: 19 26 73.1%
Branches: 18 36 50.0%

Line Branch Exec Source
1 //
2 // Copyright (c) 2022 CNRS INRIA LORIA
3 //
4 // This file is part of tsid
5 // tsid is free software: you can redistribute it
6 // and/or modify it under the terms of the GNU Lesser General Public
7 // License as published by the Free Software Foundation, either version
8 // 3 of the License, or (at your option) any later version.
9 // tsid is distributed in the hope that it will be
10 // useful, but WITHOUT ANY WARRANTY; without even the implied warranty
11 // of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
12 // General Lesser Public License for more details. You should have
13 // received a copy of the GNU Lesser General Public License along with
14 // tsid If not, see <http://www.gnu.org/licenses/>.
15 //
16
17 #ifndef __tsid_python_measured_6d_wrench_hpp__
18 #define __tsid_python_measured_6d_wrench_hpp__
19
20 #include "tsid/bindings/python/fwd.hpp"
21 #include "tsid/contacts/measured-6d-wrench.hpp"
22 #include "tsid/robots/robot-wrapper.hpp"
23 #include "pinocchio/multibody/data.hpp"
24
25 namespace tsid {
26 namespace python {
27 namespace bp = boost::python;
28
29 template <typename Measured6dWrench>
30 struct Measured6dWrenchPythonVisitor
31 : public boost::python::def_visitor<
32 Measured6dWrenchPythonVisitor<Measured6dWrench> > {
33 template <class PyClass>
34 8 void visit(PyClass &cl) const {
35 cl
36 // Expose the constructor:
37
4/8
✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8 times.
✗ Branch 5 not taken.
✓ Branch 7 taken 8 times.
✗ Branch 8 not taken.
✓ Branch 10 taken 8 times.
✗ Branch 11 not taken.
16 .def(bp::init<std::string, typename Measured6dWrench::RobotWrapper &,
38 std::string>(
39
2/4
✓ Branch 2 taken 8 times.
✗ Branch 3 not taken.
✓ Branch 5 taken 8 times.
✗ Branch 6 not taken.
24 (bp::arg("name"), bp::arg("robot"), bp::arg("frameName")),
40 "Constructor for Measured6dwrench"))
41
42 // Expose the name getter and setter:
43
1/2
✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
8 .add_property("name", &Measured6dWrenchPythonVisitor::getName,
44 &Measured6dWrenchPythonVisitor::setName,
45 "Get or set the name of the measured-6Dwrench instance")
46
47 // Expose computeJointTorques(Data &data)
48
2/4
✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8 times.
✗ Branch 5 not taken.
16 .def("computeJointTorques",
49 &Measured6dWrenchPythonVisitor::computeJointTorques,
50 bp::args("data"),
51 "Compute the joint torques from the measured contact force")
52
53 // Expose setMeasuredContactForce(const Vector6 &fext)
54
2/4
✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8 times.
✗ Branch 5 not taken.
16 .def("setMeasuredContactForce",
55 &Measured6dWrenchPythonVisitor::setMeasuredContactForce,
56 bp::args("fext"), "Set the measured contact force")
57
58 // Expose getMeasuredContactForce() as a read-only property.
59
2/4
✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8 times.
✗ Branch 5 not taken.
16 .add_property(
60 "measuredContactForce",
61 bp::make_function(
62 &Measured6dWrenchPythonVisitor::getMeasuredContactForce),
63 "Get the measured contact force")
64
65 // Expose useLocalFrame(bool local_frame)
66
2/4
✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
✓ Branch 4 taken 8 times.
✗ Branch 5 not taken.
8 .def("useLocalFrame", &Measured6dWrenchPythonVisitor::useLocalFrame,
67 bp::args("local_frame"),
68 "Specify whether to use the local frame for external force and "
69 "jacobian");
70 8 }
71
72 // Wrapper for name() getter.
73 static std::string getName(Measured6dWrench &self) { return self.name(); }
74
75 // Wrapper for name(const std::string &) setter.
76 static void setName(Measured6dWrench &self, const std::string &name) {
77 self.name(name);
78 }
79
80 // Wrapper for computeJointTorques(Data &data) returning by value.
81 static typename Measured6dWrench::Vector computeJointTorques(
82 Measured6dWrench &self, pinocchio::Data &data) {
83 return self.computeJointTorques(data);
84 }
85
86 // Wrapper for setMeasuredContactForce(const Vector6 &fext)
87 1 static void setMeasuredContactForce(
88 Measured6dWrench &self, const typename Measured6dWrench::Vector6 &fext) {
89 1 self.setMeasuredContactForce(fext);
90 1 }
91
92 // Wrapper for getMeasuredContactForce() returning by value.
93 1 static typename Measured6dWrench::Vector6 getMeasuredContactForce(
94 Measured6dWrench &self) {
95 1 return self.getMeasuredContactForce();
96 }
97
98 // Wrapper for useLocalFrame(bool local_frame)
99 static void useLocalFrame(Measured6dWrench &self, bool local_frame) {
100 self.useLocalFrame(local_frame);
101 }
102
103 // Function to expose the binding.
104 8 static void expose(const std::string &class_name) {
105
1/2
✓ Branch 2 taken 8 times.
✗ Branch 3 not taken.
8 std::string doc = "Bindings for tsid::contacts::Measured6dwrench";
106
1/2
✓ Branch 3 taken 8 times.
✗ Branch 4 not taken.
8 bp::class_<Measured6dWrench>(class_name.c_str(), doc.c_str(), bp::no_init)
107
1/2
✓ Branch 1 taken 8 times.
✗ Branch 2 not taken.
8 .def(Measured6dWrenchPythonVisitor<Measured6dWrench>());
108 8 }
109 };
110
111 } // namespace python
112 } // namespace tsid
113
114 #endif // __tsid_python_measured_6d_wrench_hpp__
115