Public Member Functions | Public Attributes | List of all members
robotis_manipulator_h::ManipulatorKinematicsDynamics Class Reference

#include <manipulator_h_kinematics_dynamics.h>

Public Member Functions

Eigen::MatrixXd calcCOM (Eigen::MatrixXd MC)
 
Eigen::MatrixXd calcJacobian (std::vector< int > idx)
 
Eigen::MatrixXd calcJacobianCOM (std::vector< int > idx)
 
Eigen::MatrixXd calcMC (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)
 
void forwardKinematics (int joint_ID)
 
bool inverseKinematics (int to, Eigen::MatrixXd tar_position, Eigen::MatrixXd tar_orientation, int max_iter, double ik_err)
 
bool inverseKinematics (int from, int to, Eigen::MatrixXd tar_position, Eigen::MatrixXd tar_orientation, int max_iter, double ik_err)
 
 ManipulatorKinematicsDynamics ()
 
 ManipulatorKinematicsDynamics (TreeSelect tree)
 
double totalMass (int joint_ID)
 
 ~ManipulatorKinematicsDynamics ()
 

Public Attributes

LinkDatamanipulator_link_data_ [ALL_JOINT_ID+1]
 

Detailed Description

Definition at line 33 of file manipulator_h_kinematics_dynamics.h.

Constructor & Destructor Documentation

robotis_manipulator_h::ManipulatorKinematicsDynamics::ManipulatorKinematicsDynamics ( )

Definition at line 30 of file manipulator_h_kinematics_dynamics.cpp.

robotis_manipulator_h::ManipulatorKinematicsDynamics::ManipulatorKinematicsDynamics ( TreeSelect  tree)

Definition at line 37 of file manipulator_h_kinematics_dynamics.cpp.

robotis_manipulator_h::ManipulatorKinematicsDynamics::~ManipulatorKinematicsDynamics ( )

Definition at line 33 of file manipulator_h_kinematics_dynamics.cpp.

Member Function Documentation

Eigen::MatrixXd robotis_manipulator_h::ManipulatorKinematicsDynamics::calcCOM ( Eigen::MatrixXd  MC)

Definition at line 211 of file manipulator_h_kinematics_dynamics.cpp.

Eigen::MatrixXd robotis_manipulator_h::ManipulatorKinematicsDynamics::calcJacobian ( std::vector< int >  idx)

Definition at line 253 of file manipulator_h_kinematics_dynamics.cpp.

Eigen::MatrixXd robotis_manipulator_h::ManipulatorKinematicsDynamics::calcJacobianCOM ( std::vector< int >  idx)

Definition at line 275 of file manipulator_h_kinematics_dynamics.cpp.

Eigen::MatrixXd robotis_manipulator_h::ManipulatorKinematicsDynamics::calcMC ( int  joint_ID)

Definition at line 195 of file manipulator_h_kinematics_dynamics.cpp.

Eigen::MatrixXd robotis_manipulator_h::ManipulatorKinematicsDynamics::calcVWerr ( Eigen::MatrixXd  tar_position,
Eigen::MatrixXd  curr_position,
Eigen::MatrixXd  tar_orientation,
Eigen::MatrixXd  curr_orientation 
)

Definition at line 298 of file manipulator_h_kinematics_dynamics.cpp.

std::vector< int > robotis_manipulator_h::ManipulatorKinematicsDynamics::findRoute ( int  to)

Definition at line 142 of file manipulator_h_kinematics_dynamics.cpp.

std::vector< int > robotis_manipulator_h::ManipulatorKinematicsDynamics::findRoute ( int  from,
int  to 
)

Definition at line 162 of file manipulator_h_kinematics_dynamics.cpp.

void robotis_manipulator_h::ManipulatorKinematicsDynamics::forwardKinematics ( int  joint_ID)

Definition at line 223 of file manipulator_h_kinematics_dynamics.cpp.

bool robotis_manipulator_h::ManipulatorKinematicsDynamics::inverseKinematics ( int  to,
Eigen::MatrixXd  tar_position,
Eigen::MatrixXd  tar_orientation,
int  max_iter,
double  ik_err 
)

Definition at line 312 of file manipulator_h_kinematics_dynamics.cpp.

bool robotis_manipulator_h::ManipulatorKinematicsDynamics::inverseKinematics ( int  from,
int  to,
Eigen::MatrixXd  tar_position,
Eigen::MatrixXd  tar_orientation,
int  max_iter,
double  ik_err 
)

Definition at line 377 of file manipulator_h_kinematics_dynamics.cpp.

double robotis_manipulator_h::ManipulatorKinematicsDynamics::totalMass ( int  joint_ID)

Definition at line 182 of file manipulator_h_kinematics_dynamics.cpp.

Member Data Documentation

LinkData* robotis_manipulator_h::ManipulatorKinematicsDynamics::manipulator_link_data_[ALL_JOINT_ID+1]

Definition at line 40 of file manipulator_h_kinematics_dynamics.h.


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


manipulator_h_kinematics_dynamics
Author(s): SCH
autogenerated on Mon Jun 10 2019 14:02:57