src/robots/robot-wrapper.cpp
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 
19 
20 #include <pinocchio/multibody/model.hpp>
21 #include <pinocchio/parsers/urdf.hpp>
27 
28 using namespace pinocchio;
29 using namespace tsid::math;
30 
31 namespace tsid {
32 namespace robots {
33 
34 RobotWrapper::RobotWrapper(const std::string& filename,
35  const std::vector<std::string>&, bool verbose)
36  : m_verbose(verbose) {
39  m_na = m_model.nv;
41  m_is_fixed_base = true;
42  init();
43 }
44 
45 RobotWrapper::RobotWrapper(const std::string& filename,
46  const std::vector<std::string>&,
47  const pinocchio::JointModelVariant& rootJoint,
48  bool verbose)
49  : m_verbose(verbose) {
52  m_na = m_model.nv - 6;
53  m_nq_actuated = m_model.nq - 7;
54  m_is_fixed_base = false;
55  init();
56 }
57 
59  : m_verbose(verbose) {
60  m_model = m;
61  m_model_filename = "";
62  m_na = m_model.nv - 6;
63  m_nq_actuated = m_model.nq - 7;
64  m_is_fixed_base = false;
65  init();
66 }
67 
69  bool verbose)
70  : m_verbose(verbose) {
71  m_model = m;
72  m_model_filename = "";
73  m_na = m_model.nv;
75  m_is_fixed_base = true;
76  switch (rootJoint) {
77  case FIXED_BASE_SYSTEM:
78  break;
80  m_na -= 6;
81  m_nq_actuated = m_model.nq - 7;
82  m_is_fixed_base = false;
83  default:
84  break;
85  }
86  init();
87 }
88 
90  m_rotor_inertias.setZero(m_na);
91  m_gear_ratios.setZero(m_na);
92  m_Md.setZero(m_na);
93  m_M.setZero(m_model.nv, m_model.nv);
94 }
95 
96 int RobotWrapper::nq() const { return m_model.nq; }
97 int RobotWrapper::nv() const { return m_model.nv; }
98 int RobotWrapper::na() const { return m_na; }
101 
102 const Model& RobotWrapper::model() const { return m_model; }
103 Model& RobotWrapper::model() { return m_model; }
104 
106  const Vector& v) const {
108  data.M.triangularView<Eigen::StrictlyLower>() =
109  data.M.transpose().triangularView<Eigen::StrictlyLower>();
110  // computeAllTerms does not compute the com acceleration, so we need to call
111  // centerOfMass Check this line, calling with zero acceleration at the last
112  // phase compute the CoM acceleration.
113  // pinocchio::centerOfMass(m_model, data, q,v,false);
115  pinocchio::centerOfMass(m_model, data, q, v, Eigen::VectorXd::Zero(nv()));
117 }
118 
121 
124  rotor_inertias.size() == m_rotor_inertias.size(),
125  "The size of the rotor_inertias vector is incorrect!");
127  updateMd();
128  return true;
129 }
130 
133  gear_ratios.size() == m_gear_ratios.size(),
134  "The size of the gear_ratios vector is incorrect!");
136  updateMd();
137  return true;
138 }
139 
141  m_Md =
142  m_gear_ratios.cwiseProduct(m_gear_ratios.cwiseProduct(m_rotor_inertias));
143 }
144 
146  RefVector com_acc) const {
147  com_pos = data.com[0];
148  com_vel = data.vcom[0];
149  com_acc = data.acom[0];
150 }
151 
152 const Vector3& RobotWrapper::com(const Data& data) const { return data.com[0]; }
153 
154 const Vector3& RobotWrapper::com_vel(const Data& data) const {
155  return data.vcom[0];
156 }
157 
158 const Vector3& RobotWrapper::com_acc(const Data& data) const {
159  return data.acom[0];
160 }
161 
162 const Matrix3x& RobotWrapper::Jcom(const Data& data) const { return data.Jcom; }
163 
165  m_M = data.M;
166  m_M.diagonal().tail(m_na) += m_Md;
167  return m_M;
168 }
169 
171  return data.nle;
172 }
173 
175  const Model::JointIndex index) const {
177  index < data.oMi.size(),
178  "The index needs to be less than the size of the oMi vector");
179  return data.oMi[index];
180 }
181 
183  const Model::JointIndex index) const {
185  index < data.v.size(),
186  "The index needs to be less than the size of the v vector");
187  return data.v[index];
188 }
189 
191  const Model::JointIndex index) const {
193  index < data.a.size(),
194  "The index needs to be less than the size of the a vector");
195  return data.a[index];
196 }
197 
199  const Model::JointIndex index,
200  Data::Matrix6x& J) const {
202  index < data.oMi.size(),
203  "The index needs to be less than the size of the oMi vector");
205 }
206 
208  const Model::JointIndex index,
209  Data::Matrix6x& J) const {
211  index < data.oMi.size(),
212  "The index needs to be less than the size of the oMi vector");
214 }
215 
217  const Model::FrameIndex index) const {
219  "Frame index greater than size of frame "
220  "vector in model - frame may not exist");
221  const Frame& f = m_model.frames[index];
222  return data.oMi[f.parent].act(f.placement);
223 }
224 
226  const Model::FrameIndex index,
227  SE3& framePosition) const {
229  "Frame index greater than size of frame "
230  "vector in model - frame may not exist");
231  const Frame& f = m_model.frames[index];
232  framePosition = data.oMi[f.parent].act(f.placement);
233 }
234 
236  const Model::FrameIndex index) const {
238  "Frame index greater than size of frame "
239  "vector in model - frame may not exist");
240  const Frame& f = m_model.frames[index];
241  return f.placement.actInv(data.v[f.parent]);
242 }
243 
245  const Model::FrameIndex index,
246  Motion& frameVelocity) const {
248  "Frame index greater than size of frame "
249  "vector in model - frame may not exist");
250  const Frame& f = m_model.frames[index];
251  frameVelocity = f.placement.actInv(data.v[f.parent]);
252 }
253 
255  const Data& data, const Model::FrameIndex index) const {
256  Motion v_local, v_world;
257  SE3 oMi, oMi_rotation_only;
258  framePosition(data, index, oMi);
259  frameVelocity(data, index, v_local);
260  oMi_rotation_only.rotation(oMi.rotation());
261  v_world = oMi_rotation_only.act(v_local);
262  return v_world;
263 }
264 
266  const Model::FrameIndex index) const {
268  "Frame index greater than size of frame "
269  "vector in model - frame may not exist");
270  const Frame& f = m_model.frames[index];
271  return f.placement.actInv(data.a[f.parent]);
272 }
273 
275  const Model::FrameIndex index,
276  Motion& frameAcceleration) const {
278  "Frame index greater than size of frame "
279  "vector in model - frame may not exist");
280  const Frame& f = m_model.frames[index];
281  frameAcceleration = f.placement.actInv(data.a[f.parent]);
282 }
283 
285  const Data& data, const Model::FrameIndex index) const {
286  Motion a_local, a_world;
287  SE3 oMi, oMi_rotation_only;
288  framePosition(data, index, oMi);
289  frameAcceleration(data, index, a_local);
290  oMi_rotation_only.rotation(oMi.rotation());
291  a_world = oMi_rotation_only.act(a_local);
292  return a_world;
293 }
294 
296  const Data& data, const Model::FrameIndex index) const {
298  "Frame index greater than size of frame "
299  "vector in model - frame may not exist");
300  const Frame& f = m_model.frames[index];
301  Motion a = f.placement.actInv(data.a[f.parent]);
302  Motion v = f.placement.actInv(data.v[f.parent]);
303  a.linear() += v.angular().cross(v.linear());
304  return a;
305 }
306 
308  const Model::FrameIndex index,
309  Motion& frameAcceleration) const {
311  "Frame index greater than size of frame "
312  "vector in model - frame may not exist");
313  const Frame& f = m_model.frames[index];
314  frameAcceleration = f.placement.actInv(data.a[f.parent]);
315  Motion v = f.placement.actInv(data.v[f.parent]);
316  frameAcceleration.linear() += v.angular().cross(v.linear());
317 }
318 
320  const Data& data, const Model::FrameIndex index) const {
321  Motion a_local, a_world;
322  SE3 oMi, oMi_rotation_only;
323  framePosition(data, index, oMi);
325  oMi_rotation_only.rotation(oMi.rotation());
326  a_world = oMi_rotation_only.act(a_local);
327  return a_world;
328 }
329 
331  Data::Matrix6x& J) const {
333  "Frame index greater than size of frame "
334  "vector in model - frame may not exist");
336 }
337 
339  Data::Matrix6x& J) const {
341  "Frame index greater than size of frame "
342  "vector in model - frame may not exist");
344 }
345 
347  return data.Ag;
348 }
349 
352  m_model, const_cast<Data&>(data))
353  .angular();
354 }
355 
356 void RobotWrapper::setGravity(const Motion& gravity) {
358 }
359 
360 // const Vector3 & com(Data & data,const Vector & q,
361 // const bool computeSubtreeComs = true,
362 // const bool updateKinematics = true)
363 // {
364 // return pinocchio::centerOfMass(m_model, data, q, computeSubtreeComs,
365 // updateKinematics);
366 // }
367 // const Vector3 & com(Data & data, const Vector & q, const Vector & v,
368 // const bool computeSubtreeComs = true,
369 // const bool updateKinematics = true)
370 // {
371 // return pinocchio::centerOfMass(m_model, data, q, v, computeSubtreeComs,
372 // updateKinematics);
373 // }
374 
375 } // namespace robots
376 } // namespace tsid
pinocchio::WORLD
WORLD
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
ModelTpl< context::Scalar, context::Options >::frames
FrameVector frames
tsid::robots::RobotWrapper::mass
const Matrix & mass(const Data &data)
Definition: src/robots/robot-wrapper.cpp:164
pinocchio::DataTpl
PINOCCHIO_CHECK_INPUT_ARGUMENT
#define PINOCCHIO_CHECK_INPUT_ARGUMENT(...)
tsid::robots::RobotWrapper::frameJacobianWorld
void frameJacobianWorld(Data &data, const Model::FrameIndex index, Data::Matrix6x &J) const
Definition: src/robots/robot-wrapper.cpp:330
index
index
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
pinocchio::getJointJacobian
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > getJointJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const JointIndex joint_id, const ReferenceFrame reference_frame)
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
J
J
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
demo_quadruped.com_acc
com_acc
Definition: demo_quadruped.py:139
tsid::robots::RobotWrapper::FIXED_BASE_SYSTEM
@ FIXED_BASE_SYSTEM
Definition: robots/robot-wrapper.hpp:57
f
f
tsid::math
Definition: constraint-base.hpp:26
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
demo_quadruped.q
q
Definition: demo_quadruped.py:74
robots
list robots
center-of-mass.hpp
tsid::robots::RobotWrapper::frameClassicAcceleration
Motion frameClassicAcceleration(const Data &data, const Model::FrameIndex index) const
Definition: src/robots/robot-wrapper.cpp:295
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
pinocchio::updateFramePlacements
void updateFramePlacements(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
demo_quadruped.com_pos
com_pos
Definition: demo_quadruped.py:137
robot-wrapper.hpp
frames.hpp
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
pinocchio::ccrba
const DataTpl< Scalar, Options, JointCollectionTpl >::Matrix6x & ccrba(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
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::robots::RobotWrapper::m_na
int m_na
Definition: robots/robot-wrapper.hpp:181
pinocchio::computeCentroidalMomentumTimeVariation
const DataTpl< Scalar, Options, JointCollectionTpl >::Force & computeCentroidalMomentumTimeVariation(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data)
tsid::robots::RobotWrapper::m_model_filename
std::string m_model_filename
Definition: robots/robot-wrapper.hpp:175
pinocchio::urdf::buildModel
ModelTpl< Scalar, Options, JointCollectionTpl > & buildModel(const std::shared_ptr<::urdf::ModelInterface > urdfTree, const typename ModelTpl< Scalar, Options, JointCollectionTpl >::JointModel &rootJoint, const std::string &rootJointName, ModelTpl< Scalar, Options, JointCollectionTpl > &model, const bool verbose=false, const bool mimic=false)
tsid::robots::RobotWrapper::updateMd
void updateMd()
Definition: src/robots/robot-wrapper.cpp:140
tsid::robots::RobotWrapper::momentumJacobian
const Data::Matrix6x & momentumJacobian(const Data &data) const
Definition: src/robots/robot-wrapper.cpp:346
ModelTpl< context::Scalar, context::Options >::gravity
Motion gravity
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
pinocchio::centerOfMass
const DataTpl< Scalar, Options, JointCollectionTpl >::Vector3 & centerOfMass(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const bool computeSubtreeComs=true)
a
Vec3f a
compute-all-terms.hpp
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
pinocchio::getFrameJacobian
Eigen::Matrix< Scalar, 6, Eigen::Dynamic, Options > getFrameJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const FrameIndex frame_id, const ReferenceFrame reference_frame)
tsid
Definition: bindings/python/constraint/constraint-bound.cpp:21
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::jacobianWorld
void jacobianWorld(const Data &data, const Model::JointIndex index, Data::Matrix6x &J) const
Definition: src/robots/robot-wrapper.cpp:198
ModelTpl< context::Scalar, context::Options >::nv
int nv
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::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
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
gravity
gravity
centroidal.hpp
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 >
verbose
bool verbose
tsid::robots::RobotWrapper::position
const SE3 & position(const Data &data, const Model::JointIndex index) const
Definition: src/robots/robot-wrapper.cpp:174
pinocchio::computeAllTerms
void computeAllTerms(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType > &v)
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
ModelTpl< context::Scalar, context::Options >::nq
int nq
tsid::robots::RobotWrapper::SE3
pinocchio::SE3 SE3
Definition: robots/robot-wrapper.hpp:46
demo_quadruped.com_vel
com_vel
Definition: demo_quadruped.py:138
pinocchio
jacobian.hpp
pinocchio::LOCAL
LOCAL


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