|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | PinocchioRobot () |
| Constructor and Destructor. More...
|
|
virtual | ~PinocchioRobot () |
|
void | computeInverseDynamics () |
|
void | computeInverseDynamics (Eigen::VectorXd &q, Eigen::VectorXd &v, Eigen::VectorXd &a) |
|
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. 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. 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. the femur length 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 () |
|
pinocchio::Data * | DataInInitialePose () |
|
pinocchio::Model * | Model () |
|
PRFoot * | leftFoot () |
|
PRFoot * | rightFoot () |
|
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 () |
|
Eigen::VectorXd & | currentTau () |
|
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) |
|
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 () |
|
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 |
|
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.