pinocchiorobot.hh 9.07 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
33
/*
 * 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"
#include "pinocchio/multibody/model.hpp"
34
#include "pinocchio/multibody/data.hpp"
35
#include <jrl/mal/matrixabstractlayer.hh>
Olivier Stasse's avatar
Olivier Stasse committed
36

37
38
39
40
41
42
43
namespace PatternGeneratorJRL
{
  struct PinocchioRobotFoot_t{
    se3::JointIndex associatedAnkle ;
    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
49
50
51
  };
  typedef PinocchioRobotFoot_t PRFoot ;

  class PinocchioRobot
  {
  public:
mnaveau's avatar
mnaveau committed
52
53
    // overload the new[] eigen operator
    EIGEN_MAKE_ALIGNED_OPERATOR_NEW
54

mnaveau's avatar
mnaveau committed
55
56
    /// Constructor and Destructor
    PinocchioRobot();
57
    virtual ~PinocchioRobot();
58
59
60

    /// Functions computing kinematics and dynamics
    void computeInverseDynamics();
Olivier Stasse's avatar
Olivier Stasse committed
61
62
63
    void computeInverseDynamics(Eigen::VectorXd & q,
                                Eigen::VectorXd & v,
                                Eigen::VectorXd & a);
64
65

    void computeForwardKinematics();
Olivier Stasse's avatar
Olivier Stasse committed
66
    void computeForwardKinematics(Eigen::VectorXd & q);
67

68
69
70
71
72
73
74
    void RPYToSpatialFreeFlyer(Eigen::Vector3d & rpy,
                               Eigen::Vector3d & drpy,
                               Eigen::Vector3d & ddrpy,
                               Eigen::Quaterniond & quat,
                               Eigen::Vector3d & omega,
                               Eigen::Vector3d & domega);

75
76
    /// \brief ComputeSpecializedInverseKinematics :
    /// compute POSITION (not velocity) of the joints from end effector pose
77
78
79
80
81
82
83
84
85
86
87
    /// 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,
88
    /// param 6D vector output, filled with zeros if the robot is not compatible
89
    ///
90
    virtual bool ComputeSpecializedInverseKinematics(
91
92
        const se3::JointIndex &jointRoot,
        const se3::JointIndex &jointEnd,
Olivier Stasse's avatar
Olivier Stasse committed
93
94
95
        const Eigen::Matrix4d & jointRootPosition,
        const Eigen::Matrix4d & jointEndPosition,
        Eigen::VectorXd &q);
96

97
    ///
98
99
    /// \brief testInverseKinematics :
    /// test if the robot has the good joint
100
    /// configuration to use the analitical inverse geometry
101
    /// to be overloaded if the user wants another inverse kinematics
102
103
    /// \return
    ///
104
105
106
107
108
109
110
111
112
    virtual bool testInverseKinematics();

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

114
115
116
117
118
119
120
  public :
    /// tools :
    std::vector<se3::JointIndex> jointsBetween
    ( se3::JointIndex first, se3::JointIndex second);
    std::vector<se3::JointIndex> fromRootToIt (se3::JointIndex it);

  private :
121
    // needed for the inverse geometry (ComputeSpecializedInverseKinematics)
Olivier Stasse's avatar
Olivier Stasse committed
122
123
124
125
    void getWaistFootKinematics(const Eigen::Matrix4d & jointRootPosition,
                                const Eigen::Matrix4d & jointEndPosition,
                                Eigen::VectorXd &q,
                                Eigen::Vector3d Dt);
126
    double ComputeXmax(double & Z);
Olivier Stasse's avatar
Olivier Stasse committed
127
128
129
    void getShoulderWristKinematics(const Eigen::Matrix4d & jointRootPosition,
                                    const Eigen::Matrix4d & jointEndPosition,
                                    Eigen::VectorXd &q,
130
131
                                    int side);
    void DetectAutomaticallyShoulders();
mnaveau's avatar
mnaveau committed
132
    void DetectAutomaticallyOneShoulder(se3::JointIndex aWrist,
133
134
135
136
137
138
139
140
141
                                        se3::JointIndex & aShoulder);


  public :
    /// Getters
    /// ///////
    inline se3::Data * Data()
    {return m_robotData;}
    inline se3::Data * DataInInitialePose()
mnaveau's avatar
mnaveau committed
142
    {return m_robotDataInInitialePose;}
143
144
145
146
147
148
149
150
    inline se3::Model * Model()
    {return m_robotModel;}

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

mnaveau's avatar
mnaveau committed
151
152
153
154
    inline se3::JointIndex leftWrist()
    {return m_leftWrist;}
    inline se3::JointIndex rightWrist()
    {return m_rightWrist;}
155
156
157
158
159
160
161
162
163
164
165
166

    inline se3::JointIndex chest()
    {return m_chest;}
    inline se3::JointIndex waist()
    {return m_waist;}

    inline double mass()
    {return m_mass;}

    inline se3::JointModelVector & getActuatedJoints()
    {return m_robotModel->joints;}

Olivier Stasse's avatar
Olivier Stasse committed
167
    inline Eigen::VectorXd currentConfiguration()
168
    {return m_qmal;}
Olivier Stasse's avatar
Olivier Stasse committed
169
    inline Eigen::VectorXd currentVelocity()
170
    {return m_vmal;}
Olivier Stasse's avatar
Olivier Stasse committed
171
    inline Eigen::VectorXd currentAcceleration()
172
173
174
175
176
    {return m_amal;}

    inline unsigned numberDof()
    {return m_robotModel->nv;}

Olivier Stasse's avatar
Olivier Stasse committed
177
    inline void zeroMomentumPoint(Eigen::Vector3d & zmp)
178
    {
179
      m_externalForces = m_robotData->liMi[1].act(m_robotData->f[1]);
180
181
      m_f = m_externalForces.linear() ;
      m_n = m_externalForces.angular() ;
182
183
184
185
186
      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
187
    inline void positionCenterOfMass(Eigen::Vector3d & com)
188
189
190
191
192
193
    {
      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
194
195
196
    inline void CenterOfMass(Eigen::Vector3d &   com,
                             Eigen::Vector3d &  dcom,
                             Eigen::Vector3d & ddcom)
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
    {
      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) ;
    }
213
214
215

    /// SETTERS
    /// ///////
Olivier Stasse's avatar
Olivier Stasse committed
216
    inline void currentConfiguration(Eigen::VectorXd conf)
217
    {m_qmal=conf;}
Olivier Stasse's avatar
Olivier Stasse committed
218
    inline void currentVelocity(Eigen::VectorXd vel)
219
    {m_vmal=vel;}
Olivier Stasse's avatar
Olivier Stasse committed
220
    inline void currentAcceleration(Eigen::VectorXd acc)
221
222
    {m_amal=acc;}

mnaveau's avatar
mnaveau committed
223
224
225
226
227
228
229
230
231
232
233
234
235
236
    /// Initialization functions
    /// ////////////////////////
    inline bool isInitialized()
    {
      return m_boolModel && m_boolData && m_boolLeftFoot && m_boolRightFoot;
    }
    bool checkModel(se3::Model * robotModel);
    bool initializeRobotModelAndData(se3::Model * robotModel,
                                     se3::Data * robotData);
    bool initializeLeftFoot(PRFoot leftFoot);
    bool initializeRightFoot(PRFoot rightFoot);

    /// Attributes
    /// //////////
mnaveau's avatar
mnaveau committed
237
238
239
240
241
242
243
244
245
  private :
    se3::Model * m_robotModel ;
    se3::Data * m_robotDataInInitialePose ; // internal variable
    se3::Data * m_robotData ;
    PRFoot m_leftFoot , m_rightFoot ;
    double m_mass ;
    se3::JointIndex m_chest, m_waist, m_leftShoulder, m_rightShoulder ;
    se3::JointIndex m_leftWrist , m_rightWrist ;

Olivier Stasse's avatar
Olivier Stasse committed
246
247
248
    Eigen::VectorXd m_qmal ;
    Eigen::VectorXd m_vmal ;
    Eigen::VectorXd m_amal ;
mnaveau's avatar
mnaveau committed
249
250
251
252
253
254
    Eigen::VectorXd m_q ;
    Eigen::VectorXd m_v ;
    Eigen::VectorXd m_a ;

    // tmp variables
    Eigen::Quaterniond m_quat ;
255
    Eigen::Matrix3d m_rot ;
256
    se3::Force m_externalForces ; // external forces and torques
257
    Eigen::VectorXd m_tau ; // external forces and torques
mnaveau's avatar
mnaveau committed
258
259
    Eigen::Vector3d m_f,m_n; // external forces and torques
    Eigen::Vector3d m_com; // multibody CoM
260
261
    Eigen::Matrix3d m_S ;
    Eigen::Vector3d m_rpy,m_drpy,m_ddrpy,m_omega,m_domega ;
mnaveau's avatar
mnaveau committed
262

263
264
    // Variables extracted form the urdf used for the analitycal inverse
    // kinematic
265
266
267
    bool m_isLegInverseKinematic ;
    bool m_isArmInverseKinematic ;

268
    // length between the waist and the hip
Olivier Stasse's avatar
Olivier Stasse committed
269
    Eigen::Vector3d m_leftDt, m_rightDt ;
270
    double m_femurLength ;
271
272
    double m_tibiaLengthZ ;
    double m_tibiaLengthY ;
273
274


mnaveau's avatar
mnaveau committed
275
276
277
278
    bool m_boolModel     ;
    bool m_boolData      ;
    bool m_boolLeftFoot  ;
    bool m_boolRightFoot ;
mnaveau's avatar
mnaveau committed
279
280
281

  }; //PinocchioRobot
}// namespace PatternGeneratorJRL
282
#endif // PinocchioRobot_HH