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::Artic Class Reference

A kinematics class for articulated (6-axis) robot arm Artic implement the kinematics of articulated (6-axis) robot arm. More...

#include <artic.h>

Inheritance diagram for rb::kin::Artic:
Inheritance graph
[legend]
Collaboration diagram for rb::kin::Artic:
Collaboration graph
[legend]

Public Member Functions

 Artic ()
 Default Constructor.
 
 Artic (const rb::math::VectorX &a0, const rb::math::VectorX &alpha0, const rb::math::VectorX &d0, const rb::math::VectorX &ini_theta, const rb::math::VectorX &uplimit0, const rb::math::VectorX &lowlimit0)
 Constructor with certain robot arm data. More...
 
 Artic (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. More...
 
 ~Artic ()
 Destructor.
 
ArmPose forwardKin (const rb::math::VectorX &q, const bool update=true) override
 Compute forward Kinematics for given angle, update each joint value, and return current current position and orientation of TCP. More...
 
IK_RESULT inverseKin (const rb::math::Matrix4 &world_tcp_tf, rb::math::VectorX &joints, ArmAxisValue &all_sols) override
 Compute inverse kinematics for given transformation matrix of TCP in Cartesian coordination system. More...
 
IK_RESULT inverseKin (const double &x, const double &y, const double &z, const double &roll, const double &pitch, const double &yaw, rb::math::VectorX &joints, ArmAxisValue &all_sols)
 Compute inverse kinematics for given position and orientation in Cartesian coordination system. More...
 
void solvePitchPitchIK (const double &th1_rad, const rb::math::Vector4 &p0, const std::vector< bool > &config, ArmAxisValue &all_sols)
 Compute inverse kinematics for two links (pitch-pitch) structure by given first joint. More...
 
void solveRowPitchRowIK (const double &th1_rad, const std::vector< bool > &config, const rb::math::Matrix4 &flange_tr, ArmAxisValue &all_sols)
 Compute inverse kinematics for wrist mechanism (row-pitch-row) structure by given first joint. More...
 
IK_RESULT solutionCheck (ArmAxisValue &sols)
 Find the solutions in all_sols that is most fit to previous joints value. More...
 
void preCheck (const int &njoint, double &rad)
 Check the value of individual joint depend join limits. More...
 
ArmPose getArmPose (void) const
 Get the position and orientation of the flange of robot arm. More...
 
rb::math::VectorX getA (void) const
 Get the link length a value between each joint of the robot arm. More...
 
rb::math::VectorX getAlpha (void) const
 Get the link twist $\alpha$ value between each joint of the robot arm. More...
 
rb::math::VectorX getD (void) const
 Get the link offset d value between each joint of the robot arm. More...
 
rb::math::VectorX getTheta (void) const
 Get the joint angle $\theta$ value of each joint of the robot arm. More...
 
void setUpLimit (rb::math::VectorX &up_lim)
 Set the upper limits of joint angles for the robot arm. More...
 
rb::math::VectorX getUpLimit (void) const
 Get the upper limits of joint angles of the robot arm. More...
 
void setLowLimit (rb::math::VectorX &low_lim)
 Set the lower limits of joint angles for the robot arm. More...
 
rb::math::VectorX getLowLimit (void) const
 Get the lower limits of joint angles of the robot arm. More...
 
- Public Member Functions inherited from rb::kin::KinematicChain
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.
 
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

rb::math::VectorX a
 Link length data member of modified D-H parameter for robot arm. More...
 
rb::math::VectorX alpha
 Link twist data member of modified D-H parameter for robot arm. More...
 
rb::math::VectorX d
 Link offset data member of modified D-H parameter for robot arm. More...
 
rb::math::VectorX theta
 Joint angle data member of modified D-H parameter for robot arm. More...
 
rb::math::VectorX up_lim_
 Upper limit of all joints.
 
rb::math::VectorX low_lim_
 Lower limit of all joints.
 
- Protected Attributes inherited from rb::kin::KinematicChain
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 articulated (6-axis) robot arm Artic implement the kinematics of articulated (6-axis) robot arm.

Constructor & Destructor Documentation

rb::kin::Artic::Artic ( const rb::math::VectorX a0,
const rb::math::VectorX alpha0,
const rb::math::VectorX d0,
const rb::math::VectorX ini_theta,
const rb::math::VectorX uplimit0,
const rb::math::VectorX lowlimit0 
)

Constructor with certain robot arm data.

Parameters
a0Link length of all links (mm)
alpha0Twist angle of all links (degree)
d0Link offset of all links (mm)
ini_thetaInitial value of all joint angles
uplimit0Upper limit of all joints
lowlimit0Lower limit of all joints

Here is the call graph for this function:

rb::kin::Artic::Artic ( 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.

Parameters
linksA vector of link that construct the articulated robot arm
baseHT matrix of robot base with respected to world coordination
toolHT matrix of TCP with respected to robot flange (last joint)
gravityGravity set as a vector.
manufactorthe name of manufactor of the robot
modelthe model of the robot named by its manufactor

Here is the call graph for this function:

Member Function Documentation

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

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

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

Reimplemented from rb::kin::KinematicChain.

Here is the call graph for this function:

rb::math::VectorX rb::kin::Artic::getA ( void  ) const

Get the link length a value between each joint of the robot arm.

Returns
rb::math::VectorX
rb::math::VectorX rb::kin::Artic::getAlpha ( void  ) const

Get the link twist $\alpha$ value between each joint of the robot arm.

Returns
rb::math::VectorX
ArmPose rb::kin::Artic::getArmPose ( void  ) const

Get the position and orientation of the flange of robot arm.

Returns
ArmPose
rb::math::VectorX rb::kin::Artic::getD ( void  ) const

Get the link offset d value between each joint of the robot arm.

Returns
rb::math::VectorX
rb::math::VectorX rb::kin::Artic::getLowLimit ( void  ) const

Get the lower limits of joint angles of the robot arm.

Returns
rb::math::VectorX
rb::math::VectorX rb::kin::Artic::getTheta ( void  ) const

Get the joint angle $\theta$ value of each joint of the robot arm.

Returns
rb::math::VectorX
rb::math::VectorX rb::kin::Artic::getUpLimit ( void  ) const

Get the upper limits of joint angles of the robot arm.

Returns
rb::math::VectorX
IK_RESULT rb::kin::Artic::inverseKin ( const rb::math::Matrix4 world_tcp_tf,
rb::math::VectorX joints,
ArmAxisValue all_sols 
)
overridevirtual

Compute inverse kinematics for given transformation 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.

Implements rb::kin::KinematicChain.

Here is the call graph for this function:

IK_RESULT rb::kin::Artic::inverseKin ( const double &  x,
const double &  y,
const double &  z,
const double &  roll,
const double &  pitch,
const double &  yaw,
rb::math::VectorX joints,
ArmAxisValue all_sols 
)

Compute inverse kinematics for given position and orientation in Cartesian coordination system.

Returns
IK_RESULT a enumerator indicates the result of inverse kinematics.
Parameters
xx value of the position.
yy value of the position.
zz value of the position.
rollroll value of the orientation.
pitchpitch value of the orientation.
yawyaw value of the orientation.
jointsthe best fittest IK solution.
all_solsa data structure to store all possible solutions.

Here is the call graph for this function:

void rb::kin::Artic::preCheck ( const int &  njoint,
double &  rad 
)

Check the value of individual joint depend join limits.

Will map map the value to corrected range if possible.

Parameters
njointindex of joint indicate which joint is examined.
radthe value of joint will be check and update as output.

Here is the caller graph for this function:

void rb::kin::Artic::setLowLimit ( rb::math::VectorX low_lim)

Set the lower limits of joint angles for the robot arm.

Parameters
low_limAn rb::math::VectorX contain the lower limit of all joints.
void rb::kin::Artic::setUpLimit ( rb::math::VectorX up_lim)

Set the upper limits of joint angles for the robot arm.

Parameters
up_limAn rb::math::VectorX contain the upper limit of all joints.
IK_RESULT rb::kin::Artic::solutionCheck ( ArmAxisValue sols)

Find the solutions in all_sols that is most fit to previous joints value.

Parameters
solsa structure to storage all possible solutions of inverse kinematics.

Here is the caller graph for this function:

void rb::kin::Artic::solvePitchPitchIK ( const double &  th1_rad,
const rb::math::Vector4 p0,
const std::vector< bool > &  config,
ArmAxisValue all_sols 
)

Compute inverse kinematics for two links (pitch-pitch) structure by given first joint.

Parameters
th1_radangle (radian) of first joint.
p0the position of wrist point wrt joint 0 (base)
configa vector of 3 bits to indicator 8 configuration (solutions) of robot arm.
all_sols
Returns

Here is the call graph for this function:

Here is the caller graph for this function:

void rb::kin::Artic::solveRowPitchRowIK ( const double &  th1_rad,
const std::vector< bool > &  config,
const rb::math::Matrix4 flange_tr,
ArmAxisValue all_sols 
)

Compute inverse kinematics for wrist mechanism (row-pitch-row) structure by given first joint.

Parameters
th1_radangle (radian) of first joint.
configa vector of 3 bits to indicator 8 configuration (solutions) of robot arm.
flange_tra H.T. Matrix of robot flange with respect to it base.
all_solsa structure to storage all possible solutions of inverse kinematics.

Here is the call graph for this function:

Here is the caller graph for this function:

Member Data Documentation

rb::math::VectorX rb::kin::Artic::a
protected

Link length data member of modified D-H parameter for robot arm.

Link length (mm)

rb::math::VectorX rb::kin::Artic::alpha
protected

Link twist data member of modified D-H parameter for robot arm.

Link twist angle (degree)

rb::math::VectorX rb::kin::Artic::d
protected

Link offset data member of modified D-H parameter for robot arm.

Link offset (mm)

rb::math::VectorX rb::kin::Artic::theta
protected

Joint angle data member of modified D-H parameter for robot arm.

Joint angle (degree)


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