RobotArmLib  0.0.4
Robot Arm Library [WIP]
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Pages
Public Member Functions | Protected Attributes | List of all members
rb::kin::KinematicChain Class Referenceabstract

A kinematics class for general serial links. More...

#include <kinematic_chain.h>

Inheritance diagram for rb::kin::KinematicChain:
Inheritance graph
[legend]

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW KinematicChain ()
 Default Constuctor.
 
 KinematicChain (std::vector< rb::kin::Link * > &links, rb::math::Matrix4 base=rb::math::Matrix4::Identity(), rb::math::Matrix4 tool=rb::math::Matrix4::Identity(), rb::math::Vector3 gravity={0., 0., rb::math::GRAVITY}, std::string manufactor="None", std::string model="None")
 Constructor with a Links vector and other parameter.
 
virtual ~KinematicChain ()
 Destructor.
 
virtual ArmPose forwardKin (const rb::math::VectorX &q, const bool update=true)
 Compute forward Kinematics for given angle, update each joint value, and return current current position and orientation of TCP. More...
 
virtual IK_RESULT inverseKin (const rb::math::Matrix4 &world_tcp_tf, rb::math::VectorX &joints, ArmAxisValue &all_sols)=0
 Compute inverse kinematics for given tranformation matrix of TCP in Cartesian coordination system. More...
 
rb::math::Matrix4 homoTrans (double &A, double &alpha, double &D, const double &theta)
 Compute homogeneous transformation matrix for given link properties, and return the matrix. More...
 
bool setTool (const ArmPose &tool_pose)
 Set the HT matrix of the offset b/w the arm flange and equipped tool or end-effector. More...
 
bool getTool (ArmPose &tool_pose) const
 Get the HT matrix of the offset b/w the arm flange and equipped tool or end-effector. More...
 
void setBase (const rb::math::Matrix4 &base)
 Set the Homogeneous Transformation matrix of the working base of the robot arm. More...
 
rb::math::Matrix4 getBase (void) const
 Get the HT matrix of the working base of the robot arm. More...
 
rb::math::Matrix4 getTCP (void) const
 Get the HT matrix of TCP w.r.t world coordination. More...
 
void setDOF (void)
 Set the degree of freedom according to the property of links. More...
 
int getDOF (void) const
 Get the degree of freedom of this kinematic chain. More...
 

Protected Attributes

std::vector< rb::kin::Link * > links_
 A vector of Link class. More...
 
std::vector< rb::math::Matrix4 * > frames_
 < A vector of HT matrix to the pose of each joint and TCP. More...
 
int dof_
 A integer indicates the degree of freedom.
 
rb::math::Matrix4 base_tf_
 HT matrix of robot base with respected to world coordination.
 
rb::math::Matrix4 tool_tf_
 HT matrix of TCP with respected to robot flange (last joint)
 
rb::math::Matrix4 world_tcp_tf_
 HT matrix of TCP with respected to world coordination. More...
 
rb::math::Vector3 gravity_
 Gravity set as a vector. More...
 
std::string manufactor_
 the name of manufactor of the robot
 
std::string model_
 the model of the robot named by its manufactor
 

Detailed Description

A kinematics class for general serial links.

KinematicChain implement the kinematics of general serial links

Member Function Documentation

ArmPose rb::kin::KinematicChain::forwardKin ( const rb::math::VectorX q,
const bool  update = true 
)
virtual

Compute forward Kinematics for given angle, update each joint value, and return current current position and orientation of TCP.

Parameters
qAn array of joint value (degree or mm).
updateA boolean to check if update the value of joints and frames.
Returns
a structure include position and orientation of TCP.

Reimplemented in rb::kin::Artic.

Here is the call graph for this function:

rb::math::Matrix4 rb::kin::KinematicChain::getBase ( void  ) const

Get the HT matrix of the working base of the robot arm.

Returns
rb::math::Matrix4
int rb::kin::KinematicChain::getDOF ( void  ) const

Get the degree of freedom of this kinematic chain.

Returns

Here is the caller graph for this function:

rb::math::Matrix4 rb::kin::KinematicChain::getTCP ( void  ) const

Get the HT matrix of TCP w.r.t world coordination.

Returns
bool rb::kin::KinematicChain::getTool ( ArmPose tool_pose) const

Get the HT matrix of the offset b/w the arm flange and equipped tool or end-effector.

Parameters
tool_pose
Returns
bool Check if setting success
rb::math::Matrix4 rb::kin::KinematicChain::homoTrans ( double &  A,
double &  alpha,
double &  D,
const double &  theta 
)

Compute homogeneous transformation matrix for given link properties, and return the matrix.

Building HT matrix A function to build homogeneous transformation matrix for each link.

Parameters
AGiven link length.
alphaGiven link twist.
DGiven link offset.
thetaGiven joint angle.
Returns
Homogeneous transformation matrix of given link properties.
Matrix4

Here is the caller graph for this function:

virtual IK_RESULT rb::kin::KinematicChain::inverseKin ( const rb::math::Matrix4 world_tcp_tf,
rb::math::VectorX joints,
ArmAxisValue all_sols 
)
pure virtual

Compute inverse kinematics for given tranformation matrix of TCP in Cartesian coordination system.

Returns
IK_RESULT a enumerator indicates the result of inverse kinematics.
Parameters
world_tcp_tfTransformation of tcp in world coordination.
jointsThe best fittest solution.
all_solsA data structure to store all possible solutions.

Implemented in rb::kin::Artic.

void rb::kin::KinematicChain::setBase ( const rb::math::Matrix4 base)

Set the Homogeneous Transformation matrix of the working base of the robot arm.

Parameters
basea Homogeneous Transformation matrix from World -> the robot base.
Returns
void rb::kin::KinematicChain::setDOF ( void  )

Set the degree of freedom according to the property of links.

Returns

Here is the caller graph for this function:

bool rb::kin::KinematicChain::setTool ( const ArmPose tool_pose)

Set the HT matrix of the offset b/w the arm flange and equipped tool or end-effector.

Parameters
tool_pose
Returns
Check if setting success

Member Data Documentation

std::vector<rb::math::Matrix4*> rb::kin::KinematicChain::frames_
protected

< A vector of HT matrix to the pose of each joint and TCP.

rb::math::Vector3 rb::kin::KinematicChain::gravity_
protected

Gravity set as a vector.

std::vector<rb::kin::Link*> rb::kin::KinematicChain::links_
protected

A vector of Link class.

rb::math::Matrix4 rb::kin::KinematicChain::world_tcp_tf_
protected

HT matrix of TCP with respected to world coordination.


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