PatternGeneratorJRL::PinocchioRobot Class Reference

#include <jrl/walkgen/pinocchiorobot.hh>

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW PinocchioRobot ()
 Constructor and Destructor. More...
 
virtual ~PinocchioRobot ()
 
void computeInverseDynamics ()
 Compute RNEA algorithm This is a front end for computeInverseDynamics(q,v,a). More...
 
void computeInverseDynamics (Eigen::VectorXd &q, Eigen::VectorXd &v, Eigen::VectorXd &a)
 Compute RNEA algorithm from. More...
 
void computeForwardKinematics ()
 Compute the geometry of the robot. More...
 
void RPYToSpatialFreeFlyer (Eigen::Vector3d &rpy, Eigen::Vector3d &drpy, Eigen::Vector3d &ddrpy, Eigen::Quaterniond &quat, Eigen::Vector3d &omega, Eigen::Vector3d &domega)
 
virtual bool ComputeSpecializedInverseKinematics (const pinocchio::JointIndex &jointRoot, const pinocchio::JointIndex &jointEnd, const Eigen::Matrix4d &jointRootPosition, const Eigen::Matrix4d &jointEndPosition, Eigen::VectorXd &q)
 ComputeSpecializedInverseKinematics : compute POSITION (not velocity) of the joints from end effector pose 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. More...
 
virtual bool testArmsInverseKinematics ()
 testArmsInverseKinematics : test if the robot arms has the good joint configuration to use the analitical inverse geometry to be overloaded if the user wants another inverse kinematics RY-RX-RZ-RY-RZ-RY More...
 
virtual bool testLegsInverseKinematics ()
 testLegsInverseKinematics : test if the robot legs has the good joint configuration to use the analitical inverse geometry to be overloaded if the user wants another inverse kinematics Two modes are available: FF-RZ-RX-RY-RY-RY-RX FF-RX-RZ-RY-RY-RY-RX More...
 
virtual bool testOneModeOfLegsInverseKinematics (std::vector< std::string > &leftLegJointNames, std::vector< std::string > &rightLegJointNames)
 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 More...
 
virtual void initializeLegsInverseKinematics ()
 initializeInverseKinematics : initialize the internal data for the inverse kinematic e.g. More...
 
std::vector< pinocchio::JointIndex > jointsBetween (pinocchio::JointIndex first, pinocchio::JointIndex second)
 tools : More...
 
std::vector< pinocchio::JointIndex > fromRootToIt (pinocchio::JointIndex it)
 
pinocchio::Data * Data ()
 Getters ///////. More...
 
pinocchio::Data * DataInInitialePose ()
 
pinocchio::Model * Model ()
 
PRFootleftFoot ()
 
PRFootrightFoot ()
 
pinocchio::JointIndex leftWrist ()
 
pinocchio::JointIndex rightWrist ()
 
pinocchio::JointIndex chest ()
 
pinocchio::JointIndex waist ()
 
double mass ()
 
pinocchio::JointModelVector & getActuatedJoints ()
 
Eigen::VectorXd & currentPinoConfiguration ()
 
Eigen::VectorXd & currentRPYConfiguration ()
 
Eigen::VectorXd & currentPinoVelocity ()
 
Eigen::VectorXd & currentPinoAcceleration ()
 
Eigen::VectorXd & currentRPYVelocity ()
 
Eigen::VectorXd & currentRPYAcceleration ()
 
unsigned numberDof ()
 
unsigned numberVelDof ()
 
void zeroMomentumPoint (Eigen::Vector3d &zmp)
 
void positionCenterOfMass (Eigen::Vector3d &com)
 
void CenterOfMass (Eigen::Vector3d &com, Eigen::Vector3d &dcom, Eigen::Vector3d &ddcom)
 
void currentPinoConfiguration (Eigen::VectorXd &conf)
 SETTERS ///////. More...
 
void currentRPYConfiguration (Eigen::VectorXd &)
 
void currentPinoVelocity (Eigen::VectorXd &vel)
 
void currentPinoAcceleration (Eigen::VectorXd &acc)
 
void currentRPYVelocity (Eigen::VectorXd &vel)
 
void currentRPYAcceleration (Eigen::VectorXd &acc)
 
pinocchio::JointIndex getFreeFlyerSize () const
 
pinocchio::JointIndex getFreeFlyerVelSize () const
 
bool isInitialized ()
 Initialization functions ////////////////////////. More...
 
bool checkModel (pinocchio::Model *robotModel)
 
bool initializeRobotModelAndData (pinocchio::Model *robotModel, pinocchio::Data *robotData)
 
bool initializeLeftFoot (PRFoot leftFoot)
 
bool initializeRightFoot (PRFoot rightFoot)
 
const std::string & getName () const
 

Constructor & Destructor Documentation

EIGEN_MAKE_ALIGNED_OPERATOR_NEW PatternGeneratorJRL::PinocchioRobot::PinocchioRobot ( )

Constructor and Destructor.

virtual PatternGeneratorJRL::PinocchioRobot::~PinocchioRobot ( )
virtual

Member Function Documentation

void PatternGeneratorJRL::PinocchioRobot::CenterOfMass ( Eigen::Vector3d &  com,
Eigen::Vector3d &  dcom,
Eigen::Vector3d &  ddcom 
)
inline
bool PatternGeneratorJRL::PinocchioRobot::checkModel ( pinocchio::Model *  robotModel)
pinocchio::JointIndex PatternGeneratorJRL::PinocchioRobot::chest ( )
inline
void PatternGeneratorJRL::PinocchioRobot::computeForwardKinematics ( )

Compute the geometry of the robot.

void PatternGeneratorJRL::PinocchioRobot::computeInverseDynamics ( )

Compute RNEA algorithm This is a front end for computeInverseDynamics(q,v,a).

Referenced by PatternGeneratorJRL::ZMPPreviewControlWithMultiBodyZMP::EvaluateMultiBodyZMP().

void PatternGeneratorJRL::PinocchioRobot::computeInverseDynamics ( Eigen::VectorXd &  q,
Eigen::VectorXd &  v,
Eigen::VectorXd &  a 
)

Compute RNEA algorithm from.

Parameters
[in]q\(q=[r,\theta,\hat{q}]\) with \(r\) the position of the free floating base (usually the waist), \(theta\) the free floating orientation in RPY format, ${q}$ the motor angles position.
virtual bool PatternGeneratorJRL::PinocchioRobot::ComputeSpecializedInverseKinematics ( const pinocchio::JointIndex &  jointRoot,
const pinocchio::JointIndex &  jointEnd,
const Eigen::Matrix4d &  jointRootPosition,
const Eigen::Matrix4d &  jointEndPosition,
Eigen::VectorXd &  q 
)
virtual

ComputeSpecializedInverseKinematics : compute POSITION (not velocity) of the joints from end effector pose 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, param 6D vector output, filled with zeros if the robot is not compatible

Eigen::VectorXd& PatternGeneratorJRL::PinocchioRobot::currentPinoAcceleration ( )
inline
void PatternGeneratorJRL::PinocchioRobot::currentPinoAcceleration ( Eigen::VectorXd &  acc)
inline
Eigen::VectorXd& PatternGeneratorJRL::PinocchioRobot::currentPinoConfiguration ( )
inline
void PatternGeneratorJRL::PinocchioRobot::currentPinoConfiguration ( Eigen::VectorXd &  conf)

SETTERS ///////.

Eigen::VectorXd& PatternGeneratorJRL::PinocchioRobot::currentPinoVelocity ( )
inline
void PatternGeneratorJRL::PinocchioRobot::currentPinoVelocity ( Eigen::VectorXd &  vel)
inline
void PatternGeneratorJRL::PinocchioRobot::currentRPYAcceleration ( Eigen::VectorXd &  acc)
inline
void PatternGeneratorJRL::PinocchioRobot::currentRPYConfiguration ( Eigen::VectorXd &  )
void PatternGeneratorJRL::PinocchioRobot::currentRPYVelocity ( Eigen::VectorXd &  vel)
inline
pinocchio::Data* PatternGeneratorJRL::PinocchioRobot::Data ( )
inline

Getters ///////.

pinocchio::Data* PatternGeneratorJRL::PinocchioRobot::DataInInitialePose ( )
inline
std::vector<pinocchio::JointIndex> PatternGeneratorJRL::PinocchioRobot::fromRootToIt ( pinocchio::JointIndex  it)
pinocchio::JointModelVector& PatternGeneratorJRL::PinocchioRobot::getActuatedJoints ( )
inline
pinocchio::JointIndex PatternGeneratorJRL::PinocchioRobot::getFreeFlyerSize ( ) const
inline
pinocchio::JointIndex PatternGeneratorJRL::PinocchioRobot::getFreeFlyerVelSize ( ) const
inline
const std::string& PatternGeneratorJRL::PinocchioRobot::getName ( ) const
bool PatternGeneratorJRL::PinocchioRobot::initializeLeftFoot ( PRFoot  leftFoot)
virtual void PatternGeneratorJRL::PinocchioRobot::initializeLegsInverseKinematics ( )
virtual

initializeInverseKinematics : initialize the internal data for the inverse kinematic e.g.

the femur length

Returns
bool PatternGeneratorJRL::PinocchioRobot::initializeRightFoot ( PRFoot  rightFoot)
bool PatternGeneratorJRL::PinocchioRobot::initializeRobotModelAndData ( pinocchio::Model *  robotModel,
pinocchio::Data *  robotData 
)
bool PatternGeneratorJRL::PinocchioRobot::isInitialized ( )
inline

Initialization functions ////////////////////////.

std::vector<pinocchio::JointIndex> PatternGeneratorJRL::PinocchioRobot::jointsBetween ( pinocchio::JointIndex  first,
pinocchio::JointIndex  second 
)

tools :

PRFoot* PatternGeneratorJRL::PinocchioRobot::leftFoot ( )
inline
pinocchio::JointIndex PatternGeneratorJRL::PinocchioRobot::leftWrist ( )
inline
double PatternGeneratorJRL::PinocchioRobot::mass ( )
inline
pinocchio::Model* PatternGeneratorJRL::PinocchioRobot::Model ( )
inline
unsigned PatternGeneratorJRL::PinocchioRobot::numberDof ( )
inline
unsigned PatternGeneratorJRL::PinocchioRobot::numberVelDof ( )
inline
void PatternGeneratorJRL::PinocchioRobot::positionCenterOfMass ( Eigen::Vector3d &  com)
inline
PRFoot* PatternGeneratorJRL::PinocchioRobot::rightFoot ( )
inline
pinocchio::JointIndex PatternGeneratorJRL::PinocchioRobot::rightWrist ( )
inline
void PatternGeneratorJRL::PinocchioRobot::RPYToSpatialFreeFlyer ( Eigen::Vector3d &  rpy,
Eigen::Vector3d &  drpy,
Eigen::Vector3d &  ddrpy,
Eigen::Quaterniond &  quat,
Eigen::Vector3d &  omega,
Eigen::Vector3d &  domega 
)
virtual bool PatternGeneratorJRL::PinocchioRobot::testArmsInverseKinematics ( )
virtual

testArmsInverseKinematics : test if the robot arms has the good joint configuration to use the analitical inverse geometry to be overloaded if the user wants another inverse kinematics RY-RX-RZ-RY-RZ-RY

Returns
virtual bool PatternGeneratorJRL::PinocchioRobot::testLegsInverseKinematics ( )
virtual

testLegsInverseKinematics : test if the robot legs has the good joint configuration to use the analitical inverse geometry to be overloaded if the user wants another inverse kinematics Two modes are available: FF-RZ-RX-RY-RY-RY-RX FF-RX-RZ-RY-RY-RY-RX

Returns
virtual bool PatternGeneratorJRL::PinocchioRobot::testOneModeOfLegsInverseKinematics ( std::vector< std::string > &  leftLegJointNames,
std::vector< std::string > &  rightLegJointNames 
)
virtual

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

Returns
pinocchio::JointIndex PatternGeneratorJRL::PinocchioRobot::waist ( )
inline
void PatternGeneratorJRL::PinocchioRobot::zeroMomentumPoint ( Eigen::Vector3d &  zmp)
inline