tsid  1.8.0
Efficient Task Space Inverse Dynamics for Multi-body Systems based on Pinocchio
measured-6d-wrench.hpp
Go to the documentation of this file.
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 
23 #include "pinocchio/multibody/data.hpp"
24 
25 namespace tsid {
26 namespace python {
27 namespace bp = boost::python;
28 
29 template <typename Measured6dWrench>
31  : public boost::python::def_visitor<
32  Measured6dWrenchPythonVisitor<Measured6dWrench> > {
33  template <class PyClass>
34  void visit(PyClass &cl) const {
35  cl
36  // Expose the constructor:
37  .def(bp::init<std::string, typename Measured6dWrench::RobotWrapper &,
38  std::string>(
39  (bp::arg("name"), bp::arg("robot"), bp::arg("frameName")),
40  "Constructor for Measured6dwrench"))
41 
42  // Expose the name getter and setter:
43  .add_property("name", &Measured6dWrenchPythonVisitor::getName,
45  "Get or set the name of the measured-6Dwrench instance")
46 
47  // Expose computeJointTorques(Data &data)
48  .def("computeJointTorques",
50  bp::args("data"),
51  "Compute the joint torques from the measured contact force")
52 
53  // Expose setMeasuredContactForce(const Vector6 &fext)
54  .def("setMeasuredContactForce",
56  bp::args("fext"), "Set the measured contact force")
57 
58  // Expose getMeasuredContactForce() as a read-only property.
59  .add_property(
60  "measuredContactForce",
61  bp::make_function(
63  "Get the measured contact force")
64 
65  // Expose useLocalFrame(bool local_frame)
66  .def("useLocalFrame", &Measured6dWrenchPythonVisitor::useLocalFrame,
67  bp::args("local_frame"),
68  "Specify whether to use the local frame for external force and "
69  "jacobian");
70  }
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.
82  Measured6dWrench &self, pinocchio::Data &data) {
83  return self.computeJointTorques(data);
84  }
85 
86  // Wrapper for setMeasuredContactForce(const Vector6 &fext)
88  Measured6dWrench &self, const typename Measured6dWrench::Vector6 &fext) {
89  self.setMeasuredContactForce(fext);
90  }
91 
92  // Wrapper for getMeasuredContactForce() returning by value.
94  Measured6dWrench &self) {
95  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  static void expose(const std::string &class_name) {
105  std::string doc = "Bindings for tsid::contacts::Measured6dwrench";
106  bp::class_<Measured6dWrench>(class_name.c_str(), doc.c_str(), bp::no_init)
108  }
109 };
110 
111 } // namespace python
112 } // namespace tsid
113 
114 #endif // __tsid_python_measured_6d_wrench_hpp__
pinocchio::Data Data
Definition: inverse-dynamics-formulation-acc-force.cpp:30
Eigen::Matrix< Scalar, 6, 1 > Vector6
Definition: fwd.hpp:41
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: fwd.hpp:35
Definition: constraint-bound.hpp:25
Definition: measured-6d-wrench.hpp:32
void visit(PyClass &cl) const
Definition: measured-6d-wrench.hpp:34
static void setName(Measured6dWrench &self, const std::string &name)
Definition: measured-6d-wrench.hpp:76
static Measured6dWrench::Vector computeJointTorques(Measured6dWrench &self, pinocchio::Data &data)
Definition: measured-6d-wrench.hpp:81
static std::string getName(Measured6dWrench &self)
Definition: measured-6d-wrench.hpp:73
static void useLocalFrame(Measured6dWrench &self, bool local_frame)
Definition: measured-6d-wrench.hpp:99
static void setMeasuredContactForce(Measured6dWrench &self, const typename Measured6dWrench::Vector6 &fext)
Definition: measured-6d-wrench.hpp:87
static Measured6dWrench::Vector6 getMeasuredContactForce(Measured6dWrench &self)
Definition: measured-6d-wrench.hpp:93
static void expose(const std::string &class_name)
Definition: measured-6d-wrench.hpp:104