robots/robot-wrapper.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2017 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 __invdyn_robot_wrapper_hpp__
19 #define __invdyn_robot_wrapper_hpp__
20 
21 #include "tsid/deprecated.hh"
22 #include "tsid/math/fwd.hpp"
23 #include "tsid/robots/fwd.hpp"
24 
25 #include <pinocchio/multibody/model.hpp>
26 #include <pinocchio/multibody/data.hpp>
27 #include <pinocchio/spatial/fwd.hpp>
28 
29 #include <string>
30 #include <vector>
31 
32 namespace tsid {
33 namespace robots {
37 class RobotWrapper {
38  public:
39  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
40 
54 
55  /* Possible root joints */
56  typedef enum e_RootJointType {
59  } RootJointType;
60 
61  RobotWrapper(const std::string& filename,
62  const std::vector<std::string>& package_dirs,
63  bool verbose = false);
64 
65  RobotWrapper(const std::string& filename,
66  const std::vector<std::string>& package_dirs,
67  const pinocchio::JointModelVariant& rootJoint,
68  bool verbose = false);
69 
70  TSID_DEPRECATED RobotWrapper(const Model& m, bool verbose = false);
71 
72  RobotWrapper(const Model& m, RootJointType rootJoint, bool verbose = false);
73 
74  virtual ~RobotWrapper() = default;
75 
76  virtual int nq() const;
77  virtual int nq_actuated() const;
78  virtual int nv() const;
79  virtual int na() const;
80  virtual bool is_fixed_base() const;
81 
87  const Model& model() const;
88  Model& model();
89 
90  void computeAllTerms(Data& data, const Vector& q, const Vector& v) const;
91 
92  const Vector& rotor_inertias() const;
93  const Vector& gear_ratios() const;
94 
97 
99  RefVector com_acc) const;
100 
101  const Vector3& com(const Data& data) const;
102 
103  const Vector3& com_vel(const Data& data) const;
104 
105  const Vector3& com_acc(const Data& data) const;
106 
107  const Matrix3x& Jcom(const Data& data) const;
108 
109  const Matrix& mass(const Data& data);
110 
111  const Vector& nonLinearEffects(const Data& data) const;
112 
113  const SE3& position(const Data& data, const Model::JointIndex index) const;
114 
115  const Motion& velocity(const Data& data, const Model::JointIndex index) const;
116 
117  const Motion& acceleration(const Data& data,
118  const Model::JointIndex index) const;
119 
120  void jacobianWorld(const Data& data, const Model::JointIndex index,
121  Data::Matrix6x& J) const;
122 
123  void jacobianLocal(const Data& data, const Model::JointIndex index,
124  Data::Matrix6x& J) const;
125 
126  SE3 framePosition(const Data& data, const Model::FrameIndex index) const;
127 
128  void framePosition(const Data& data, const Model::FrameIndex index,
129  SE3& framePosition) const;
130 
131  Motion frameVelocity(const Data& data, const Model::FrameIndex index) const;
132 
134  const Model::FrameIndex index) const;
135 
136  void frameVelocity(const Data& data, const Model::FrameIndex index,
137  Motion& frameVelocity) const;
138 
140  const Model::FrameIndex index) const;
141 
143  const Model::FrameIndex index) const;
144 
145  void frameAcceleration(const Data& data, const Model::FrameIndex index,
146  Motion& frameAcceleration) const;
147 
149  const Model::FrameIndex index) const;
150 
152  const Data& data, const Model::FrameIndex index) const;
153 
154  void frameClassicAcceleration(const Data& data, const Model::FrameIndex index,
155  Motion& frameAcceleration) const;
156 
157  void frameJacobianWorld(Data& data, const Model::FrameIndex index,
158  Data::Matrix6x& J) const;
159 
160  void frameJacobianLocal(Data& data, const Model::FrameIndex index,
161  Data::Matrix6x& J) const;
162 
163  const Data::Matrix6x& momentumJacobian(const Data& data) const;
164 
166 
167  void setGravity(const Motion& gravity);
168 
169  protected:
170  void init();
171  void updateMd();
172 
175  std::string m_model_filename;
176  bool m_verbose;
177 
179  int m_na;
182  bool m_is_fixed_base;
188 };
189 
190 } // namespace robots
191 
192 } // namespace tsid
193 
194 #endif // ifndef __invdyn_robot_wrapper_hpp__
tsid::robots::RobotWrapper::framePosition
SE3 framePosition(const Data &data, const Model::FrameIndex index) const
Definition: src/robots/robot-wrapper.cpp:216
demo_quadruped.v
v
Definition: demo_quadruped.py:80
tsid::robots::RobotWrapper::is_fixed_base
virtual bool is_fixed_base() const
Definition: src/robots/robot-wrapper.cpp:100
tsid::robots::RobotWrapper::m_rotor_inertias
Vector m_rotor_inertias
Definition: robots/robot-wrapper.hpp:184
tsid::robots::RobotWrapper::frameVelocity
Motion frameVelocity(const Data &data, const Model::FrameIndex index) const
Definition: src/robots/robot-wrapper.cpp:235
tsid::robots::RobotWrapper::frameClassicAccelerationWorldOriented
Motion frameClassicAccelerationWorldOriented(const Data &data, const Model::FrameIndex index) const
Definition: src/robots/robot-wrapper.cpp:319
tsid::robots::RobotWrapper::mass
const Matrix & mass(const Data &data)
Definition: src/robots/robot-wrapper.cpp:164
pinocchio::DataTpl
tsid::robots::RobotWrapper::frameJacobianWorld
void frameJacobianWorld(Data &data, const Model::FrameIndex index, Data::Matrix6x &J) const
Definition: src/robots/robot-wrapper.cpp:330
pinocchio::SE3
context::SE3 SE3
tsid::robots::RobotWrapper::nonLinearEffects
const Vector & nonLinearEffects(const Data &data) const
Definition: src/robots/robot-wrapper.cpp:170
tsid::robots::RobotWrapper::velocity
const Motion & velocity(const Data &data, const Model::JointIndex index) const
Definition: src/robots/robot-wrapper.cpp:182
setup.data
data
Definition: setup.in.py:48
tsid::robots::RobotWrapper::angularMomentumTimeVariation
Vector3 angularMomentumTimeVariation(const Data &data) const
Definition: src/robots/robot-wrapper.cpp:350
tsid::math::Matrix3x
Eigen::Matrix< Scalar, 3, Eigen::Dynamic > Matrix3x
Definition: math/fwd.hpp:42
tsid::robots::RobotWrapper::m_gear_ratios
Vector m_gear_ratios
Definition: robots/robot-wrapper.hpp:185
tsid::robots::RobotWrapper::Vector
math::Vector Vector
Definition: robots/robot-wrapper.hpp:47
tsid::robots::RobotWrapper::setGravity
void setGravity(const Motion &gravity)
Definition: src/robots/robot-wrapper.cpp:356
tsid::robots::RobotWrapper::m_is_fixed_base
bool m_is_fixed_base
Definition: robots/robot-wrapper.hpp:183
tsid::robots::RobotWrapper::m_model
Model m_model
Robot model.
Definition: robots/robot-wrapper.hpp:174
tsid::robots::RobotWrapper::FLOATING_BASE_SYSTEM
@ FLOATING_BASE_SYSTEM
Definition: robots/robot-wrapper.hpp:58
tsid::robots::RobotWrapper::gear_ratios
const Vector & gear_ratios() const
Definition: src/robots/robot-wrapper.cpp:120
tsid::robots::RobotWrapper::FIXED_BASE_SYSTEM
@ FIXED_BASE_SYSTEM
Definition: robots/robot-wrapper.hpp:57
tsid::math::Vector6
Eigen::Matrix< Scalar, 6, 1 > Vector6
Definition: math/fwd.hpp:41
pinocchio::FrameTpl
tsid::robots::RobotWrapper::rotor_inertias
const Vector & rotor_inertias() const
Definition: src/robots/robot-wrapper.cpp:119
ModelTpl< context::Scalar, context::Options >::JointIndex
pinocchio::JointIndex JointIndex
tsid::robots::RobotWrapper::ConstRefVector
math::ConstRefVector ConstRefVector
Definition: robots/robot-wrapper.hpp:53
tsid::robots::RobotWrapper::e_RootJointType
e_RootJointType
Definition: robots/robot-wrapper.hpp:56
demo_quadruped.q
q
Definition: demo_quadruped.py:74
robots
list robots
tsid::robots::RobotWrapper::frameClassicAcceleration
Motion frameClassicAcceleration(const Data &data, const Model::FrameIndex index) const
Definition: src/robots/robot-wrapper.cpp:295
tsid::robots::RobotWrapper::Frame
pinocchio::Frame Frame
Definition: robots/robot-wrapper.hpp:45
tsid::robots::RobotWrapper::Vector3
math::Vector3 Vector3
Definition: robots/robot-wrapper.hpp:48
tsid::robots::RobotWrapper::nv
virtual int nv() const
Definition: src/robots/robot-wrapper.cpp:97
tsid::robots::RobotWrapper::nq_actuated
virtual int nq_actuated() const
Definition: src/robots/robot-wrapper.cpp:99
tsid::robots::RobotWrapper::model
const Model & model() const
Accessor to model.
Definition: src/robots/robot-wrapper.cpp:102
demo_quadruped.com_pos
com_pos
Definition: demo_quadruped.py:137
tsid::math::RefVector
Eigen::Ref< Vector > RefVector
Definition: math/fwd.hpp:47
tsid::robots::RobotWrapper::~RobotWrapper
virtual ~RobotWrapper()=default
pinocchio::JointModelVariant
JointCollectionDefault::JointModelVariant JointModelVariant
tsid::robots::RobotWrapper::com
void com(const Data &data, RefVector com_pos, RefVector com_vel, RefVector com_acc) const
Definition: src/robots/robot-wrapper.cpp:145
fwd.hpp
ModelTpl< context::Scalar, context::Options >::FrameIndex
pinocchio::FrameIndex FrameIndex
tsid::robots::RobotWrapper::Matrix3x
math::Matrix3x Matrix3x
Definition: robots/robot-wrapper.hpp:51
tsid::robots::RobotWrapper::RefVector
math::RefVector RefVector
Definition: robots/robot-wrapper.hpp:52
tsid::robots::RobotWrapper::frameJacobianLocal
void frameJacobianLocal(Data &data, const Model::FrameIndex index, Data::Matrix6x &J) const
Definition: src/robots/robot-wrapper.cpp:338
tsid::math::Matrix
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic > Matrix
Definition: math/fwd.hpp:36
tsid::robots::RobotWrapper::m_na
int m_na
Definition: robots/robot-wrapper.hpp:181
tsid::robots::RobotWrapper::m_model_filename
std::string m_model_filename
Definition: robots/robot-wrapper.hpp:175
tsid::robots::RobotWrapper::updateMd
void updateMd()
Definition: src/robots/robot-wrapper.cpp:140
tsid::math::ConstRefVector
const typedef Eigen::Ref< const Vector > ConstRefVector
Definition: math/fwd.hpp:48
tsid::robots::RobotWrapper::momentumJacobian
const Data::Matrix6x & momentumJacobian(const Data &data) const
Definition: src/robots/robot-wrapper.cpp:346
tsid::robots::RobotWrapper::Motion
pinocchio::Motion Motion
Definition: robots/robot-wrapper.hpp:44
tsid::math::Vector
Eigen::Matrix< Scalar, Eigen::Dynamic, 1 > Vector
Definition: math/fwd.hpp:35
tsid::robots::RobotWrapper::m_verbose
bool m_verbose
Definition: robots/robot-wrapper.hpp:176
tsid::robots::RobotWrapper::computeAllTerms
void computeAllTerms(Data &data, const Vector &q, const Vector &v) const
Definition: src/robots/robot-wrapper.cpp:105
tsid::robots::RobotWrapper::jacobianLocal
void jacobianLocal(const Data &data, const Model::JointIndex index, Data::Matrix6x &J) const
Definition: src/robots/robot-wrapper.cpp:207
tsid::robots::RobotWrapper::m_nq_actuated
int m_nq_actuated
Definition: robots/robot-wrapper.hpp:178
fwd.hpp
tsid::math::Scalar
double Scalar
Definition: math/fwd.hpp:34
tsid
Definition: bindings/python/constraint/constraint-bound.cpp:21
tsid::robots::RobotWrapper::Data
pinocchio::Data Data
Definition: robots/robot-wrapper.hpp:43
tsid::robots::RobotWrapper::nq
virtual int nq() const
Definition: src/robots/robot-wrapper.cpp:96
test_Constraint.m
int m
Definition: test_Constraint.py:41
tsid::robots::RobotWrapper
Wrapper for a robot based on pinocchio.
Definition: robots/robot-wrapper.hpp:37
tsid::robots::RobotWrapper::jacobianWorld
void jacobianWorld(const Data &data, const Model::JointIndex index, Data::Matrix6x &J) const
Definition: src/robots/robot-wrapper.cpp:198
tsid::robots::RobotWrapper::frameVelocityWorldOriented
Motion frameVelocityWorldOriented(const Data &data, const Model::FrameIndex index) const
Definition: src/robots/robot-wrapper.cpp:254
tsid::robots::RobotWrapper::acceleration
const Motion & acceleration(const Data &data, const Model::JointIndex index) const
Definition: src/robots/robot-wrapper.cpp:190
tsid::robots::RobotWrapper::init
void init()
Definition: src/robots/robot-wrapper.cpp:89
tsid::robots::RobotWrapper::m_Md
Vector m_Md
Definition: robots/robot-wrapper.hpp:186
tsid::robots::RobotWrapper::Jcom
const Matrix3x & Jcom(const Data &data) const
Definition: src/robots/robot-wrapper.cpp:162
pinocchio::DataTpl::Matrix6x
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > Matrix6x
tsid::robots::RobotWrapper::Matrix
math::Matrix Matrix
Definition: robots/robot-wrapper.hpp:50
tsid::robots::RobotWrapper::RobotWrapper
RobotWrapper(const std::string &filename, const std::vector< std::string > &package_dirs, bool verbose=false)
Definition: src/robots/robot-wrapper.cpp:34
tsid::robots::RobotWrapper::Model
pinocchio::Model Model
Definition: robots/robot-wrapper.hpp:42
tsid::robots::RobotWrapper::m_M
Matrix m_M
diagonal part of inertia matrix due to rotor inertias
Definition: robots/robot-wrapper.hpp:187
tsid::robots::RobotWrapper::RootJointType
enum tsid::robots::RobotWrapper::e_RootJointType RootJointType
tsid::robots::RobotWrapper::Vector6
math::Vector6 Vector6
Definition: robots/robot-wrapper.hpp:49
demo_quadruped.filename
filename
Definition: demo_quadruped.py:46
tsid::robots::RobotWrapper::com_acc
const Vector3 & com_acc(const Data &data) const
Definition: src/robots/robot-wrapper.cpp:158
pinocchio::MotionTpl
tsid::robots::RobotWrapper::Scalar
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef math::Scalar Scalar
Definition: robots/robot-wrapper.hpp:41
tsid::robots::RobotWrapper::com_vel
const Vector3 & com_vel(const Data &data) const
Definition: src/robots/robot-wrapper.cpp:154
ModelTpl< context::Scalar, context::Options >
tsid::robots::RobotWrapper::position
const SE3 & position(const Data &data, const Model::JointIndex index) const
Definition: src/robots/robot-wrapper.cpp:174
tsid::math::Vector3
Eigen::Matrix< Scalar, 3, 1 > Vector3
Definition: math/fwd.hpp:40
tsid::robots::RobotWrapper::na
virtual int na() const
Definition: src/robots/robot-wrapper.cpp:98
tsid::robots::RobotWrapper::frameAccelerationWorldOriented
Motion frameAccelerationWorldOriented(const Data &data, const Model::FrameIndex index) const
Definition: src/robots/robot-wrapper.cpp:284
tsid::robots::RobotWrapper::frameAcceleration
Motion frameAcceleration(const Data &data, const Model::FrameIndex index) const
Definition: src/robots/robot-wrapper.cpp:265
tsid::robots::RobotWrapper::SE3
pinocchio::SE3 SE3
Definition: robots/robot-wrapper.hpp:46


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