pinocchiorobot.hh 11.7 KB
Newer Older
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
/*
 * Copyright 2016,
 *
 * Maximilien Naveau
 * Olivier Stasse
 *
 * JRL, CNRS/AIST
 *
 * This file is part of jrl-walkgen.
 * jrl-walkgen is free software: you can redistribute it and/or modify
 * it under the terms of the GNU Lesser General Public License as published by
 * the Free Software Foundation, either version 3 of the License, or
 * (at your option) any later version.
 *
 * jrl-walkgen is distributed in the hope that it will be useful,
 * but WITHOUT ANY WARRANTY; without even the implied warranty of
 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 * GNU General Lesser Public License for more details.
 * You should have received a copy of the GNU Lesser General Public License
 * along with jrl-walkgen.  If not, see <http://www.gnu.org/licenses/>.
 *
 *  Research carried out within the scope of the
 *  Joint Japanese-French Robotics Laboratory (JRL)
 */
/*! \file PinocchioRobot.hh
  \brief This object defines a humanoid robot model based on the PinocchioRobot
frame work */

#ifndef PinocchioRobot_HH
#define PinocchioRobot_HH

#include "pinocchio/spatial/se3.hpp"
Olivier Stasse's avatar
Olivier Stasse committed
33
#include "pinocchio/multibody/data.hpp"
34
#include "pinocchio/multibody/model.hpp"
35
#include "pinocchio/parsers/urdf.hpp"
Olivier Stasse's avatar
Olivier Stasse committed
36

37
38
39
namespace PatternGeneratorJRL
{
  struct PinocchioRobotFoot_t{
Olivier Stasse's avatar
Olivier Stasse committed
40
    pinocchio::JointIndex associatedAnkle ;
41
42
43
    double soleDepth ; // z axis
    double soleWidth ; // y axis
    double soleHeight ;// x axis
Olivier Stasse's avatar
Olivier Stasse committed
44
    Eigen::Vector3d anklePosition ;
45
    EIGEN_MAKE_ALIGNED_OPERATOR_NEW
46
47
48
  };
  typedef PinocchioRobotFoot_t PRFoot ;

49
50
51
52
53
54
  namespace pinocchio_robot
  {
    const int RPY_SIZE=6;
    const int QUATERNION_SIZE=7;
  }
  
55
56
57
  class PinocchioRobot
  {
  public:
mnaveau's avatar
mnaveau committed
58
59
    // overload the new[] eigen operator
    EIGEN_MAKE_ALIGNED_OPERATOR_NEW
60

mnaveau's avatar
mnaveau committed
61
62
    /// Constructor and Destructor
    PinocchioRobot();
63
    virtual ~PinocchioRobot();
64
65
66

    /// Functions computing kinematics and dynamics
    void computeInverseDynamics();
Olivier Stasse's avatar
Olivier Stasse committed
67
68
69
    void computeInverseDynamics(Eigen::VectorXd & q,
                                Eigen::VectorXd & v,
                                Eigen::VectorXd & a);
70
71

    void computeForwardKinematics();
72
73
    /// q should be given in RPY convention.
    //    void computeForwardKinematics(Eigen::VectorXd & q);
74

75
76
77
78
79
80
81
    void RPYToSpatialFreeFlyer(Eigen::Vector3d & rpy,
                               Eigen::Vector3d & drpy,
                               Eigen::Vector3d & ddrpy,
                               Eigen::Quaterniond & quat,
                               Eigen::Vector3d & omega,
                               Eigen::Vector3d & domega);

82
83
    /// \brief ComputeSpecializedInverseKinematics :
    /// compute POSITION (not velocity) of the joints from end effector pose
84
85
86
87
88
89
90
91
92
93
94
    /// This is the implementation of the analitycal inverse kinematic extracted
    /// from the book of Kajita
    /// Authors Shuuji Kajita ; Hirohisa Hirukawa ; Kensuke Harada ; Kazuhito Yokoi
    /// ISBN 9782287877162 ; 9782287877155
    /// It needs a specific distribution of the joint to work.
    /// a test at the initialization of the class is [should be] done to check
    /// if everything is correct
    /// param root joint index, i.e. the waist or the shoulder
    /// param end joint index, i.e, the wrist or ankle indexes
    /// param root joint homogenous matrix position,
    /// param root joint homogenous matrix index,
95
    /// param 6D vector output, filled with zeros if the robot is not compatible
96
    ///
97
    virtual bool ComputeSpecializedInverseKinematics(
Olivier Stasse's avatar
Olivier Stasse committed
98
99
        const pinocchio::JointIndex &jointRoot,
        const pinocchio::JointIndex &jointEnd,
Olivier Stasse's avatar
Olivier Stasse committed
100
101
102
        const Eigen::Matrix4d & jointRootPosition,
        const Eigen::Matrix4d & jointEndPosition,
        Eigen::VectorXd &q);
103

104
    ///
105
106
    /// \brief testArmsInverseKinematics :
    /// test if the robot arms has the good joint
107
    /// configuration to use the analitical inverse geometry
108
    /// to be overloaded if the user wants another inverse kinematics
109
    /// RY-RX-RZ-RY-RZ-RY
110
111
    /// \return
    ///
112
113
114
115
    virtual bool testArmsInverseKinematics();
    ///
    /// \brief testLegsInverseKinematics :
    /// test if the robot legs has the good joint
116
    /// configuration to use the analitical inverse geometry
117
    /// to be overloaded if the user wants another inverse kinematics
118
119
120
    /// Two modes are available:
    /// FF-RZ-RX-RY-RY-RY-RX
    /// FF-RX-RZ-RY-RY-RY-RX
121
    /// \return
122
    ///
123
    virtual bool testLegsInverseKinematics();
124
    ///
125
126
127
128
129
    /// \brief testOneModefOfLegInverseKinematics :
    /// test if the robot legs has one good joint
    /// configuration to use the analitical inverse geometry
    /// to be overloaded if the user wants another inverse kinematics
    /// \return
130
    ///
131
132
133
    virtual bool testOneModeOfLegsInverseKinematics
    (std::vector<std::string> &leftLegJointNames,
     std::vector<std::string> &rightLegJointNames);
134
135
136
137
138
139
140

    ///
    /// \brief initializeInverseKinematics :
    /// initialize the internal data for the inverse kinematic e.g. the femur
    /// length
    /// \return
    ///
141
    virtual void initializeLegsInverseKinematics();
142

143
144
  public :
    /// tools :
Olivier Stasse's avatar
Olivier Stasse committed
145
146
147
    std::vector<pinocchio::JointIndex> jointsBetween
    ( pinocchio::JointIndex first, pinocchio::JointIndex second);
    std::vector<pinocchio::JointIndex> fromRootToIt (pinocchio::JointIndex it);
148
149

  private :
150
    // needed for the inverse geometry (ComputeSpecializedInverseKinematics)
Olivier Stasse's avatar
Olivier Stasse committed
151
152
153
    void getWaistFootKinematics(const Eigen::Matrix4d & jointRootPosition,
                                const Eigen::Matrix4d & jointEndPosition,
                                Eigen::VectorXd &q,
154
                                Eigen::Vector3d &Dt) const;
155
    double ComputeXmax(double & Z);
Olivier Stasse's avatar
Olivier Stasse committed
156
157
158
    void getShoulderWristKinematics(const Eigen::Matrix4d & jointRootPosition,
                                    const Eigen::Matrix4d & jointEndPosition,
                                    Eigen::VectorXd &q,
159
160
                                    int side);
    void DetectAutomaticallyShoulders();
Olivier Stasse's avatar
Olivier Stasse committed
161
162
    void DetectAutomaticallyOneShoulder(pinocchio::JointIndex aWrist,
                                        pinocchio::JointIndex & aShoulder);
163

164
165
166
167
168
    /*! \brief Computes the size of the free flyer/root robot
      loads by the urdf.
      Set the value of m_PinoFreeFlyerSize.
    */
    void ComputeRootSize();
169
170
171
172

  public :
    /// Getters
    /// ///////
Olivier Stasse's avatar
Olivier Stasse committed
173
    inline pinocchio::Data * Data()
174
    {return m_robotData;}
Olivier Stasse's avatar
Olivier Stasse committed
175
    inline pinocchio::Data * DataInInitialePose()
mnaveau's avatar
mnaveau committed
176
    {return m_robotDataInInitialePose;}
Olivier Stasse's avatar
Olivier Stasse committed
177
    inline pinocchio::Model * Model()
178
179
180
181
182
183
184
    {return m_robotModel;}

    inline PRFoot * leftFoot()
    {return &m_leftFoot;}
    inline PRFoot * rightFoot()
    {return &m_rightFoot;}

Olivier Stasse's avatar
Olivier Stasse committed
185
    inline pinocchio::JointIndex leftWrist()
mnaveau's avatar
mnaveau committed
186
    {return m_leftWrist;}
Olivier Stasse's avatar
Olivier Stasse committed
187
    inline pinocchio::JointIndex rightWrist()
mnaveau's avatar
mnaveau committed
188
    {return m_rightWrist;}
189

Olivier Stasse's avatar
Olivier Stasse committed
190
    inline pinocchio::JointIndex chest()
191
    {return m_chest;}
Olivier Stasse's avatar
Olivier Stasse committed
192
    inline pinocchio::JointIndex waist()
193
194
195
196
197
    {return m_waist;}

    inline double mass()
    {return m_mass;}

Olivier Stasse's avatar
Olivier Stasse committed
198
    inline pinocchio::JointModelVector & getActuatedJoints()
199
200
    {return m_robotModel->joints;}

201
202
203
204
205
206
207
208
209
210
211
212
    inline Eigen::VectorXd & currentPinoConfiguration()
    {return m_qpino;}
    inline Eigen::VectorXd & currentRPYConfiguration()
    {return m_qrpy;}    
    inline Eigen::VectorXd & currentPinoVelocity()
    {return m_vpino;}
    inline Eigen::VectorXd & currentPinoAcceleration()
    {return m_apino;}
    inline Eigen::VectorXd & currentRPYVelocity()
    {return m_vrpy;}
    inline Eigen::VectorXd & currentRPYAcceleration()
    {return m_arpy;}
213
214

    inline unsigned numberDof()
215
216
217
    {return m_robotModel->nq;}

    inline unsigned numberVelDof()
218
219
    {return m_robotModel->nv;}

Olivier Stasse's avatar
Olivier Stasse committed
220
    inline void zeroMomentumPoint(Eigen::Vector3d & zmp)
221
    {
222
      m_externalForces = m_robotData->liMi[1].act(m_robotData->f[1]);
223
224
      m_f = m_externalForces.linear() ;
      m_n = m_externalForces.angular() ;
225
226
227
228
229
      zmp(0) = -m_n(1)/m_f(2) ;
      zmp(1) =  m_n(0)/m_f(2) ;
      zmp(2) = 0.0 ; // by default
    }

Olivier Stasse's avatar
Olivier Stasse committed
230
    inline void positionCenterOfMass(Eigen::Vector3d & com)
231
232
233
234
235
236
    {
      m_com = m_robotData->com[0] ;
      com(0) = m_com(0) ;
      com(1) = m_com(1) ;
      com(2) = m_com(2) ;
    }
Olivier Stasse's avatar
Olivier Stasse committed
237
238
239
    inline void CenterOfMass(Eigen::Vector3d &   com,
                             Eigen::Vector3d &  dcom,
                             Eigen::Vector3d & ddcom)
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
    {
      m_com = m_robotData->acom[0] ;
      ddcom(0) = m_com(0) ;
      ddcom(1) = m_com(1) ;
      ddcom(2) = m_com(2) ;

      m_com = m_robotData->vcom[0] ;
      dcom(0) = m_com(0) ;
      dcom(1) = m_com(1) ;
      dcom(2) = m_com(2) ;

      m_com = m_robotData->com[0] ;
      com(0) = m_com(0) ;
      com(1) = m_com(1) ;
      com(2) = m_com(2) ;
    }
256
257
258

    /// SETTERS
    /// ///////
259
260
261
262
263
264
265
266
267
268
    void currentPinoConfiguration(Eigen::VectorXd & conf);
    void currentRPYConfiguration(Eigen::VectorXd &);
    inline void currentPinoVelocity(Eigen::VectorXd & vel)
    {m_vpino=vel;}
    inline void currentPinoAcceleration(Eigen::VectorXd & acc)
    {m_apino=acc;}
    inline void currentRPYVelocity(Eigen::VectorXd & vel)
    {m_vrpy=vel;}
    inline void currentRPYAcceleration(Eigen::VectorXd & acc)
    {m_arpy=acc;}
269

270
271
272
273
274
275
    inline pinocchio::JointIndex getFreeFlyerSize() const
    { return m_PinoFreeFlyerSize;}

    inline pinocchio::JointIndex getFreeFlyerVelSize() const
    { return m_PinoFreeFlyerVelSize;}

mnaveau's avatar
mnaveau committed
276
277
278
279
280
281
    /// Initialization functions
    /// ////////////////////////
    inline bool isInitialized()
    {
      return m_boolModel && m_boolData && m_boolLeftFoot && m_boolRightFoot;
    }
Olivier Stasse's avatar
Olivier Stasse committed
282
283
284
    bool checkModel(pinocchio::Model * robotModel);
    bool initializeRobotModelAndData(pinocchio::Model * robotModel,
                                     pinocchio::Data * robotData);
mnaveau's avatar
mnaveau committed
285
286
287
    bool initializeLeftFoot(PRFoot leftFoot);
    bool initializeRightFoot(PRFoot rightFoot);

288
    const std::string & getName() const;
mnaveau's avatar
mnaveau committed
289
290
    /// Attributes
    /// //////////
mnaveau's avatar
mnaveau committed
291
  private :
Olivier Stasse's avatar
Olivier Stasse committed
292
293
294
    pinocchio::Model * m_robotModel ;
    pinocchio::Data * m_robotDataInInitialePose ; // internal variable
    pinocchio::Data * m_robotData ;
mnaveau's avatar
mnaveau committed
295
296
    PRFoot m_leftFoot , m_rightFoot ;
    double m_mass ;
Olivier Stasse's avatar
Olivier Stasse committed
297
298
    pinocchio::JointIndex m_chest, m_waist, m_leftShoulder, m_rightShoulder ;
    pinocchio::JointIndex m_leftWrist , m_rightWrist ;
mnaveau's avatar
mnaveau committed
299

300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
    /// Fields member to store  configurations, velocity and acceleration
    /// @{
    /// Configuration SE(3) position + quaternion + NbDofs
    Eigen::VectorXd m_qpino ;
    /// Configuration SE(3) position + RPY + NbDofs    
    Eigen::VectorXd m_qrpy ;
    /// Velocity se(3) + NbDofs
    Eigen::VectorXd m_vpino ;
    /// Velocity se(3) + NbDofs
    Eigen::VectorXd m_vrpy ;
    /// Acceleration acc + NbDofs
    Eigen::VectorXd m_apino ;
    Eigen::VectorXd m_arpy ;
    // @}

    
mnaveau's avatar
mnaveau committed
316
317
    // tmp variables
    Eigen::Quaterniond m_quat ;
318
    Eigen::Matrix3d m_rot ;
Olivier Stasse's avatar
Olivier Stasse committed
319
    pinocchio::Force m_externalForces ; // external forces and torques
320
    Eigen::VectorXd m_tau ; // external forces and torques
mnaveau's avatar
mnaveau committed
321
322
    Eigen::Vector3d m_f,m_n; // external forces and torques
    Eigen::Vector3d m_com; // multibody CoM
323
324
    Eigen::Matrix3d m_S ;
    Eigen::Vector3d m_rpy,m_drpy,m_ddrpy,m_omega,m_domega ;
mnaveau's avatar
mnaveau committed
325

326
327
    // Variables extracted form the urdf used for the analitycal inverse
    // kinematic
328
    bool m_isLegInverseKinematic ;
329
    unsigned int m_modeLegInverseKinematic;
330
331
    bool m_isArmInverseKinematic ;

332
    // length between the waist and the hip
Olivier Stasse's avatar
Olivier Stasse committed
333
    Eigen::Vector3d m_leftDt, m_rightDt ;
334
    double m_femurLength ;
335
336
    double m_tibiaLengthZ ;
    double m_tibiaLengthY ;
337
338


mnaveau's avatar
mnaveau committed
339
340
341
342
    bool m_boolModel     ;
    bool m_boolData      ;
    bool m_boolLeftFoot  ;
    bool m_boolRightFoot ;
mnaveau's avatar
mnaveau committed
343

344
345
346
347
348
349
    /// \brief Size of the free flyer configuration space.
    pinocchio::JointIndex m_PinoFreeFlyerSize;

    /// \brief Size of the free flyer velocity space.
    pinocchio::JointIndex m_PinoFreeFlyerVelSize;

mnaveau's avatar
mnaveau committed
350
351
  }; //PinocchioRobot
}// namespace PatternGeneratorJRL
352
#endif // PinocchioRobot_HH