Public Member Functions | Public Attributes | List of all members
thormang3::KinematicsDynamics Class Reference

#include <kinematics_dynamics.h>

Public Member Functions

Eigen::MatrixXd calcCenterOfMass (Eigen::MatrixXd mc)
 
void calcForwardKinematics (int joint_ID)
 
bool calcInverseKinematics (int to, Eigen::MatrixXd tar_position, Eigen::MatrixXd tar_orientation, int max_iter, double ik_err)
 
bool calcInverseKinematics (int from, int to, Eigen::MatrixXd tar_position, Eigen::MatrixXd tar_orientation, int max_iter, double ik_err)
 
bool calcInverseKinematics (int to, Eigen::MatrixXd tar_position, Eigen::MatrixXd tar_orientation, int max_iter, double ik_err, Eigen::MatrixXd weight)
 
bool calcInverseKinematics (int from, int to, Eigen::MatrixXd tar_position, Eigen::MatrixXd tar_orientation, int max_iter, double ik_err, Eigen::MatrixXd weight)
 
bool calcInverseKinematicsForLeftLeg (double *out, double x, double y, double z, double roll, double pitch, double yaw)
 
bool calcInverseKinematicsForLeg (double *out, double x, double y, double z, double roll, double pitch, double yaw)
 
bool calcInverseKinematicsForRightLeg (double *out, double x, double y, double z, double roll, double pitch, double yaw)
 
Eigen::MatrixXd calcJacobian (std::vector< int > idx)
 
Eigen::MatrixXd calcJacobianCOM (std::vector< int > idx)
 
void calcJointsCenterOfMass (int joint_id)
 
Eigen::MatrixXd calcMassCenter (int joint_id)
 
double calcTotalMass (int joint_id)
 
Eigen::MatrixXd calcVWerr (Eigen::MatrixXd tar_position, Eigen::MatrixXd curr_position, Eigen::MatrixXd tar_orientation, Eigen::MatrixXd curr_orientation)
 
std::vector< int > findRoute (int to)
 
std::vector< int > findRoute (int from, int to)
 
 KinematicsDynamics ()
 
 KinematicsDynamics (TreeSelect tree)
 
 ~KinematicsDynamics ()
 

Public Attributes

double ankle_length_m_
 
double calf_length_m_
 
double leg_side_offset_m_
 
double thigh_length_m_
 
LinkDatathormang3_link_data_ [ALL_JOINT_ID+1]
 

Detailed Description

Definition at line 45 of file kinematics_dynamics.h.

Constructor & Destructor Documentation

thormang3::KinematicsDynamics::KinematicsDynamics ( )

Definition at line 30 of file kinematics_dynamics.cpp.

thormang3::KinematicsDynamics::~KinematicsDynamics ( )

Definition at line 31 of file kinematics_dynamics.cpp.

thormang3::KinematicsDynamics::KinematicsDynamics ( TreeSelect  tree)

Definition at line 33 of file kinematics_dynamics.cpp.

Member Function Documentation

Eigen::MatrixXd thormang3::KinematicsDynamics::calcCenterOfMass ( Eigen::MatrixXd  mc)

Definition at line 753 of file kinematics_dynamics.cpp.

void thormang3::KinematicsDynamics::calcForwardKinematics ( int  joint_ID)

Definition at line 764 of file kinematics_dynamics.cpp.

bool thormang3::KinematicsDynamics::calcInverseKinematics ( int  to,
Eigen::MatrixXd  tar_position,
Eigen::MatrixXd  tar_orientation,
int  max_iter,
double  ik_err 
)

Definition at line 851 of file kinematics_dynamics.cpp.

bool thormang3::KinematicsDynamics::calcInverseKinematics ( int  from,
int  to,
Eigen::MatrixXd  tar_position,
Eigen::MatrixXd  tar_orientation,
int  max_iter,
double  ik_err 
)

Definition at line 915 of file kinematics_dynamics.cpp.

bool thormang3::KinematicsDynamics::calcInverseKinematics ( int  to,
Eigen::MatrixXd  tar_position,
Eigen::MatrixXd  tar_orientation,
int  max_iter,
double  ik_err,
Eigen::MatrixXd  weight 
)

Definition at line 979 of file kinematics_dynamics.cpp.

bool thormang3::KinematicsDynamics::calcInverseKinematics ( int  from,
int  to,
Eigen::MatrixXd  tar_position,
Eigen::MatrixXd  tar_orientation,
int  max_iter,
double  ik_err,
Eigen::MatrixXd  weight 
)

Definition at line 1063 of file kinematics_dynamics.cpp.

bool thormang3::KinematicsDynamics::calcInverseKinematicsForLeftLeg ( double *  out,
double  x,
double  y,
double  z,
double  roll,
double  pitch,
double  yaw 
)

Definition at line 1244 of file kinematics_dynamics.cpp.

bool thormang3::KinematicsDynamics::calcInverseKinematicsForLeg ( double *  out,
double  x,
double  y,
double  z,
double  roll,
double  pitch,
double  yaw 
)

Definition at line 1142 of file kinematics_dynamics.cpp.

bool thormang3::KinematicsDynamics::calcInverseKinematicsForRightLeg ( double *  out,
double  x,
double  y,
double  z,
double  roll,
double  pitch,
double  yaw 
)

Definition at line 1228 of file kinematics_dynamics.cpp.

Eigen::MatrixXd thormang3::KinematicsDynamics::calcJacobian ( std::vector< int >  idx)

Definition at line 794 of file kinematics_dynamics.cpp.

Eigen::MatrixXd thormang3::KinematicsDynamics::calcJacobianCOM ( std::vector< int >  idx)

Definition at line 815 of file kinematics_dynamics.cpp.

void thormang3::KinematicsDynamics::calcJointsCenterOfMass ( int  joint_id)

Definition at line 738 of file kinematics_dynamics.cpp.

Eigen::MatrixXd thormang3::KinematicsDynamics::calcMassCenter ( int  joint_id)

Definition at line 723 of file kinematics_dynamics.cpp.

double thormang3::KinematicsDynamics::calcTotalMass ( int  joint_id)

Definition at line 711 of file kinematics_dynamics.cpp.

Eigen::MatrixXd thormang3::KinematicsDynamics::calcVWerr ( Eigen::MatrixXd  tar_position,
Eigen::MatrixXd  curr_position,
Eigen::MatrixXd  tar_orientation,
Eigen::MatrixXd  curr_orientation 
)

Definition at line 838 of file kinematics_dynamics.cpp.

std::vector< int > thormang3::KinematicsDynamics::findRoute ( int  to)

Definition at line 671 of file kinematics_dynamics.cpp.

std::vector< int > thormang3::KinematicsDynamics::findRoute ( int  from,
int  to 
)

Definition at line 691 of file kinematics_dynamics.cpp.

Member Data Documentation

double thormang3::KinematicsDynamics::ankle_length_m_

Definition at line 83 of file kinematics_dynamics.h.

double thormang3::KinematicsDynamics::calf_length_m_

Definition at line 82 of file kinematics_dynamics.h.

double thormang3::KinematicsDynamics::leg_side_offset_m_

Definition at line 84 of file kinematics_dynamics.h.

double thormang3::KinematicsDynamics::thigh_length_m_

Definition at line 81 of file kinematics_dynamics.h.

LinkData* thormang3::KinematicsDynamics::thormang3_link_data_[ALL_JOINT_ID+1]

Definition at line 79 of file kinematics_dynamics.h.


The documentation for this class was generated from the following files:


thormang3_kinematics_dynamics
Author(s): SCH
autogenerated on Mon Jun 10 2019 15:37:49