bindings/python/robots/robot-wrapper.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2018 CNRS
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
15 // <http://www.gnu.org/licenses/>.
16 //
17 
18 #ifndef __tsid_python_robot_wrapper_hpp__
19 #define __tsid_python_robot_wrapper_hpp__
20 
22 
24 
25 namespace tsid {
26 namespace python {
27 namespace bp = boost::python;
28 
29 template <typename Robot>
31  : public boost::python::def_visitor<RobotPythonVisitor<Robot> > {
32  typedef std::vector<std::string> std_vec;
33  typedef Eigen::Matrix<double, 3, Eigen::Dynamic> Matrix3x;
34 
35  template <class PyClass>
36 
37  void visit(PyClass &cl) const {
38  cl
39  .def(bp::init<std::string, std_vec, bool>(
40  (bp::arg("filename"), bp::arg("package_dir"), bp::arg("verbose")),
41  "Default constructor without RootJoint."))
42  .def(bp::init<std::string, std_vec, pinocchio::JointModelVariant &,
43  bool>((bp::arg("filename"), bp::arg("package_dir"),
44  bp::arg("roottype"), bp::arg("verbose")),
45  "Default constructor with RootJoint."))
46  .def(bp::init<pinocchio::Model, bool>(
47  (bp::arg("Pinocchio Model"), bp::arg("verbose")),
48  "Default constructor from pinocchio model without RootJoint."))
50  bool>(
51  (bp::arg("Pinocchio Model"), bp::arg("rootJoint"),
52  bp::arg("verbose")),
53  "Default constructor from pinocchio model with RootJoint."))
54  .def("__init__",
55  bp::make_constructor(RobotPythonVisitor<Robot>::makeClass))
56  .add_property("nq", &Robot::nq)
57  .add_property("nv", &Robot::nv)
58  .add_property("na", &Robot::na)
59  .add_property("nq_actuated", &Robot::nq_actuated)
60  .add_property("is_fixed_base", &Robot::is_fixed_base)
61 
62  .def("model", &RobotPythonVisitor::model)
63  .def("data", &RobotPythonVisitor::data)
64 
65  .add_property("rotor_inertias", &RobotPythonVisitor::rotor_inertias)
66  .add_property("gear_ratios", &RobotPythonVisitor::gear_ratios)
67  .def("set_rotor_inertias", &RobotPythonVisitor::set_rotor_inertias,
68  bp::arg("inertia vector"))
69  .def("set_gear_ratios", &RobotPythonVisitor::set_gear_ratios,
70  bp::arg("gear ratio vector"))
71 
72  .def("computeAllTerms", &RobotPythonVisitor::computeAllTerms,
73  bp::args("data", "q", "v"), "compute all dynamics")
74  .def("com", &RobotPythonVisitor::com, bp::arg("data"))
75  .def("com_vel", &RobotPythonVisitor::com_vel, bp::arg("data"))
76  .def("com_acc", &RobotPythonVisitor::com_acc, bp::arg("data"))
77  .def("Jcom", &RobotPythonVisitor::Jcom, bp::arg("data"))
78  .def("mass", &RobotPythonVisitor::mass, bp::arg("data"))
79  .def("nonLinearEffect", &RobotPythonVisitor::nonLinearEffects,
80  bp::arg("data"))
81  .def("position", &RobotPythonVisitor::position,
82  bp::args("data", "index"))
83  .def("velocity", &RobotPythonVisitor::velocity,
84  bp::args("data", "index"))
85  .def("acceleration", &RobotPythonVisitor::acceleration,
86  bp::args("data", "index"))
87 
88  .def("framePosition", &RobotPythonVisitor::framePosition,
89  bp::args("data", "index"))
90  .def("frameVelocity", &RobotPythonVisitor::frameVelocity,
91  bp::args("data", "index"))
92  .def("frameAcceleration", &RobotPythonVisitor::frameAcceleration,
93  bp::args("data", "index"))
94  .def("frameClassicAcceleration",
96  bp::args("data", "index"))
97  .def("frameVelocityWorldOriented",
99  bp::args("data", "index"))
100  .def("frameAccelerationWorldOriented",
102  bp::args("data", "index"))
103  .def("frameClassicAccelerationWorldOriented",
105  bp::args("data", "index"))
106  .def("angularMomentumTimeVariation",
108  .def("setGravity", &RobotPythonVisitor::setGravity, bp::arg("gravity"));
109  }
110 
111  static boost::shared_ptr<Robot> makeClass(
112  const std::string &filename, const std::vector<std::string> &stdvec,
113  bp::object &bpObject, bool verbose) {
114  pinocchio::JointModelFreeFlyer root_joint =
115  bp::extract<pinocchio::JointModelFreeFlyer>(bpObject)();
116  boost::shared_ptr<Robot> p(
117  new tsid::robots::RobotWrapper(filename, stdvec, root_joint, verbose));
118  return p;
119  }
120 
121  static pinocchio::Model model(const Robot &self) { return self.model(); }
122  static pinocchio::Data data(const Robot &self) {
123  pinocchio::Data data(self.model());
124  return data;
125  }
126  static Eigen::VectorXd rotor_inertias(const Robot &self) {
127  return self.rotor_inertias();
128  }
129  static Eigen::VectorXd gear_ratios(const Robot &self) {
130  return self.gear_ratios();
131  }
132  static bool set_rotor_inertias(Robot &self,
133  const Eigen::VectorXd &rotor_inertias) {
134  return self.rotor_inertias(rotor_inertias);
135  }
136  static bool set_gear_ratios(Robot &self, const Eigen::VectorXd &gear_ratios) {
137  return self.gear_ratios(gear_ratios);
138  }
139 
140  static Eigen::Vector3d com(const Robot &self, const pinocchio::Data &data) {
141  return self.com(data);
142  }
143  static Eigen::Vector3d com_vel(const Robot &self,
144  const pinocchio::Data &data) {
145  return self.com_vel(data);
146  }
147  static Eigen::Vector3d com_acc(const Robot &self,
148  const pinocchio::Data &data) {
149  return self.com_acc(data);
150  }
151  static Matrix3x Jcom(const Robot &self, const pinocchio::Data &data) {
152  return self.Jcom(data);
153  }
154  static void computeAllTerms(const Robot &self, pinocchio::Data &data,
155  const Eigen::VectorXd &q,
156  const Eigen::VectorXd &v) {
157  self.computeAllTerms(data, q, v);
158  }
159  static Eigen::MatrixXd mass(Robot &self, pinocchio::Data &data) {
160  return self.mass(data);
161  }
162  static Eigen::VectorXd nonLinearEffects(const Robot &self,
163  const pinocchio::Data &data) {
164  return self.nonLinearEffects(data);
165  }
166  static pinocchio::SE3 position(const Robot &self, const pinocchio::Data &data,
167  const pinocchio::Model::JointIndex &index) {
168  return self.position(data, index);
169  }
170  static pinocchio::Motion velocity(const Robot &self,
171  const pinocchio::Data &data,
172  const pinocchio::Model::JointIndex &index) {
173  return self.velocity(data, index);
174  }
176  const Robot &self, const pinocchio::Data &data,
177  const pinocchio::Model::JointIndex &index) {
178  return self.acceleration(data, index);
179  }
181  const Robot &self, const pinocchio::Data &data,
182  const pinocchio::Model::FrameIndex &index) {
183  return self.framePosition(data, index);
184  }
186  const Robot &self, const pinocchio::Data &data,
187  const pinocchio::Model::FrameIndex &index) {
188  return self.frameVelocity(data, index);
189  }
191  const Robot &self, const pinocchio::Data &data,
192  const pinocchio::Model::FrameIndex &index) {
193  return self.frameAcceleration(data, index);
194  }
196  const Robot &self, const pinocchio::Data &data,
197  const pinocchio::Model::FrameIndex &index) {
198  return self.frameClassicAcceleration(data, index);
199  }
201  const Robot &self, const pinocchio::Data &data,
202  const pinocchio::Model::FrameIndex &index) {
203  return self.frameVelocityWorldOriented(data, index);
204  }
206  const Robot &self, const pinocchio::Data &data,
207  const pinocchio::Model::FrameIndex &index) {
208  return self.frameAccelerationWorldOriented(data, index);
209  }
211  const Robot &self, const pinocchio::Data &data,
212  const pinocchio::Model::FrameIndex &index) {
213  return self.frameClassicAccelerationWorldOriented(data, index);
214  }
215  static Eigen::Vector3d angularMomentumTimeVariation(
216  const Robot &self, const pinocchio::Data &data) {
217  return self.angularMomentumTimeVariation(data);
218  }
219  static void setGravity(Robot &self, const pinocchio::Motion &gravity) {
220  return self.setGravity(gravity);
221  }
222  static void expose(const std::string &class_name) {
223  std::string doc = "Robot Wrapper info.";
224  bp::class_<Robot>(class_name.c_str(), doc.c_str(), bp::no_init)
226  ;
227  bp::enum_<robots::RobotWrapper::RootJointType>("RootJointType")
228  .value("FIXED_BASE_SYSTEM", robots::RobotWrapper::FIXED_BASE_SYSTEM)
229  .value("FLOATING_BASE_SYSTEM",
231  .export_values();
232  }
233 };
234 } // namespace python
235 } // namespace tsid
236 
237 #endif // ifndef __tsid_python_robot_wrapper_hpp__
demo_quadruped.v
v
Definition: demo_quadruped.py:80
init
void init(bool compute_local_aabb=true)
tsid::python::RobotPythonVisitor::makeClass
static boost::shared_ptr< Robot > makeClass(const std::string &filename, const std::vector< std::string > &stdvec, bp::object &bpObject, bool verbose)
Definition: bindings/python/robots/robot-wrapper.hpp:111
tsid::python::RobotPythonVisitor
Definition: bindings/python/robots/robot-wrapper.hpp:30
tsid::python::RobotPythonVisitor::nonLinearEffects
static Eigen::VectorXd nonLinearEffects(const Robot &self, const pinocchio::Data &data)
Definition: bindings/python/robots/robot-wrapper.hpp:162
boost::python
tsid::python::RobotPythonVisitor::com_acc
static Eigen::Vector3d com_acc(const Robot &self, const pinocchio::Data &data)
Definition: bindings/python/robots/robot-wrapper.hpp:147
class_name
str class_name(str s)
pinocchio::DataTpl
tsid::python::RobotPythonVisitor::gear_ratios
static Eigen::VectorXd gear_ratios(const Robot &self)
Definition: bindings/python/robots/robot-wrapper.hpp:129
tsid::python::RobotPythonVisitor::frameVelocity
static pinocchio::Motion frameVelocity(const Robot &self, const pinocchio::Data &data, const pinocchio::Model::FrameIndex &index)
Definition: bindings/python/robots/robot-wrapper.hpp:185
tsid::python::RobotPythonVisitor::Matrix3x
Eigen::Matrix< double, 3, Eigen::Dynamic > Matrix3x
Definition: bindings/python/robots/robot-wrapper.hpp:33
index
index
pinocchio::SE3
context::SE3 SE3
tsid::python::RobotPythonVisitor::set_rotor_inertias
static bool set_rotor_inertias(Robot &self, const Eigen::VectorXd &rotor_inertias)
Definition: bindings/python/robots/robot-wrapper.hpp:132
tsid::python::RobotPythonVisitor::com_vel
static Eigen::Vector3d com_vel(const Robot &self, const pinocchio::Data &data)
Definition: bindings/python/robots/robot-wrapper.hpp:143
tsid::python::RobotPythonVisitor::frameVelocityWorldOriented
static pinocchio::Motion frameVelocityWorldOriented(const Robot &self, const pinocchio::Data &data, const pinocchio::Model::FrameIndex &index)
Definition: bindings/python/robots/robot-wrapper.hpp:200
tsid::robots::RobotWrapper::FLOATING_BASE_SYSTEM
@ FLOATING_BASE_SYSTEM
Definition: robots/robot-wrapper.hpp:58
tsid::python::RobotPythonVisitor::data
static pinocchio::Data data(const Robot &self)
Definition: bindings/python/robots/robot-wrapper.hpp:122
tsid::python::RobotPythonVisitor::std_vec
std::vector< std::string > std_vec
Definition: bindings/python/robots/robot-wrapper.hpp:32
tsid::python::RobotPythonVisitor::frameAccelerationWorldOriented
static pinocchio::Motion frameAccelerationWorldOriented(const Robot &self, const pinocchio::Data &data, const pinocchio::Model::FrameIndex &index)
Definition: bindings/python/robots/robot-wrapper.hpp:205
pinocchio::JointModelFreeFlyerTpl
tsid::python::RobotPythonVisitor::acceleration
static pinocchio::Motion acceleration(const Robot &self, const pinocchio::Data &data, const pinocchio::Model::JointIndex &index)
Definition: bindings/python/robots/robot-wrapper.hpp:175
tsid::robots::RobotWrapper::FIXED_BASE_SYSTEM
@ FIXED_BASE_SYSTEM
Definition: robots/robot-wrapper.hpp:57
tsid::python::RobotPythonVisitor::model
static pinocchio::Model model(const Robot &self)
Definition: bindings/python/robots/robot-wrapper.hpp:121
tsid::python::RobotPythonVisitor::expose
static void expose(const std::string &class_name)
Definition: bindings/python/robots/robot-wrapper.hpp:222
tsid::python::RobotPythonVisitor::setGravity
static void setGravity(Robot &self, const pinocchio::Motion &gravity)
Definition: bindings/python/robots/robot-wrapper.hpp:219
ModelTpl< context::Scalar, context::Options >::JointIndex
pinocchio::JointIndex JointIndex
demo_quadruped.q
q
Definition: demo_quadruped.py:74
p
p
ex_4_conf.nv
int nv
Definition: ex_4_conf.py:23
tsid::python::RobotPythonVisitor::velocity
static pinocchio::Motion velocity(const Robot &self, const pinocchio::Data &data, const pinocchio::Model::JointIndex &index)
Definition: bindings/python/robots/robot-wrapper.hpp:170
robot-wrapper.hpp
python
pinocchio::JointModelVariant
JointCollectionDefault::JointModelVariant JointModelVariant
tsid::python::RobotPythonVisitor::rotor_inertias
static Eigen::VectorXd rotor_inertias(const Robot &self)
Definition: bindings/python/robots/robot-wrapper.hpp:126
ModelTpl< context::Scalar, context::Options >::FrameIndex
pinocchio::FrameIndex FrameIndex
tsid::python::RobotPythonVisitor::com
static Eigen::Vector3d com(const Robot &self, const pinocchio::Data &data)
Definition: bindings/python/robots/robot-wrapper.hpp:140
tsid::python::RobotPythonVisitor::set_gear_ratios
static bool set_gear_ratios(Robot &self, const Eigen::VectorXd &gear_ratios)
Definition: bindings/python/robots/robot-wrapper.hpp:136
tsid::python::RobotPythonVisitor::framePosition
static pinocchio::SE3 framePosition(const Robot &self, const pinocchio::Data &data, const pinocchio::Model::FrameIndex &index)
Definition: bindings/python/robots/robot-wrapper.hpp:180
tsid::python::RobotPythonVisitor::position
static pinocchio::SE3 position(const Robot &self, const pinocchio::Data &data, const pinocchio::Model::JointIndex &index)
Definition: bindings/python/robots/robot-wrapper.hpp:166
tsid::python::RobotPythonVisitor::angularMomentumTimeVariation
static Eigen::Vector3d angularMomentumTimeVariation(const Robot &self, const pinocchio::Data &data)
Definition: bindings/python/robots/robot-wrapper.hpp:215
tsid
Definition: bindings/python/constraint/constraint-bound.cpp:21
tsid::python::RobotPythonVisitor::Jcom
static Matrix3x Jcom(const Robot &self, const pinocchio::Data &data)
Definition: bindings/python/robots/robot-wrapper.hpp:151
tsid::robots::RobotWrapper
Wrapper for a robot based on pinocchio.
Definition: robots/robot-wrapper.hpp:37
cl
cl
tsid::python::RobotPythonVisitor::frameClassicAccelerationWorldOriented
static pinocchio::Motion frameClassicAccelerationWorldOriented(const Robot &self, const pinocchio::Data &data, const pinocchio::Model::FrameIndex &index)
Definition: bindings/python/robots/robot-wrapper.hpp:210
tsid::python::RobotPythonVisitor::visit
void visit(PyClass &cl) const
Definition: bindings/python/robots/robot-wrapper.hpp:37
fwd.hpp
test_Tasks.na
int na
Definition: test_Tasks.py:95
tsid::python::RobotPythonVisitor::computeAllTerms
static void computeAllTerms(const Robot &self, pinocchio::Data &data, const Eigen::VectorXd &q, const Eigen::VectorXd &v)
Definition: bindings/python/robots/robot-wrapper.hpp:154
tsid::python::RobotPythonVisitor::mass
static Eigen::MatrixXd mass(Robot &self, pinocchio::Data &data)
Definition: bindings/python/robots/robot-wrapper.hpp:159
tsid::robots::RobotWrapper::RootJointType
enum tsid::robots::RobotWrapper::e_RootJointType RootJointType
tsid::python::RobotPythonVisitor::frameClassicAcceleration
static pinocchio::Motion frameClassicAcceleration(const Robot &self, const pinocchio::Data &data, const pinocchio::Model::FrameIndex &index)
Definition: bindings/python/robots/robot-wrapper.hpp:195
demo_quadruped.filename
filename
Definition: demo_quadruped.py:46
pinocchio::MotionTpl
gravity
gravity
ModelTpl< context::Scalar, context::Options >
verbose
bool verbose
tsid::python::RobotPythonVisitor::frameAcceleration
static pinocchio::Motion frameAcceleration(const Robot &self, const pinocchio::Data &data, const pinocchio::Model::FrameIndex &index)
Definition: bindings/python/robots/robot-wrapper.hpp:190


tsid
Author(s): Andrea Del Prete, Justin Carpentier
autogenerated on Thu Apr 3 2025 02:47:15