RobotArmLib
0.0.4
Robot Arm Library [WIP]
|
A kinematics class for articulated (6-axis) robot arm Artic implement the kinematics of articulated (6-axis) robot arm. More...
#include <artic.h>
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 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 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 | |
A kinematics class for articulated (6-axis) robot arm Artic implement the kinematics of articulated (6-axis) robot arm.
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.
a0 | Link length of all links (mm) |
alpha0 | Twist angle of all links (degree) |
d0 | Link offset of all links (mm) |
ini_theta | Initial value of all joint angles |
uplimit0 | Upper limit of all joints |
lowlimit0 | Lower limit of all joints |
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.
links | A vector of link that construct the articulated robot arm |
base | HT matrix of robot base with respected to world coordination |
tool | HT matrix of TCP with respected to robot flange (last joint) |
gravity | Gravity set as a vector. |
manufactor | the name of manufactor of the robot |
model | the model of the robot named by its manufactor |
|
overridevirtual |
Compute forward Kinematics for given angle, update each joint value, and return current current position and orientation of TCP.
q | An array of joint degree. |
update | A boolean to check if update the value of joints and frames. |
Reimplemented from rb::kin::KinematicChain.
rb::math::VectorX rb::kin::Artic::getA | ( | void | ) | const |
Get the link length a
value between each joint of the robot arm.
rb::math::VectorX rb::kin::Artic::getAlpha | ( | void | ) | const |
Get the link twist value between each joint of the robot arm.
ArmPose rb::kin::Artic::getArmPose | ( | void | ) | const |
Get the position and orientation of the flange of robot arm.
rb::math::VectorX rb::kin::Artic::getD | ( | void | ) | const |
Get the link offset d
value between each joint of the robot arm.
rb::math::VectorX rb::kin::Artic::getLowLimit | ( | void | ) | const |
Get the lower limits of joint angles of the robot arm.
rb::math::VectorX rb::kin::Artic::getTheta | ( | void | ) | const |
Get the joint angle value of each joint of the robot arm.
rb::math::VectorX rb::kin::Artic::getUpLimit | ( | void | ) | const |
Get the upper limits of joint angles of the robot arm.
|
overridevirtual |
Compute inverse kinematics for given transformation matrix of TCP in Cartesian coordination system.
world_tcp_tf | Transformation of tcp in world coordination. |
joints | The best fittest solution. |
all_sols | A data structure to store all possible solutions. |
Implements rb::kin::KinematicChain.
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.
x | x value of the position. |
y | y value of the position. |
z | z value of the position. |
roll | roll value of the orientation. |
pitch | pitch value of the orientation. |
yaw | yaw value of the orientation. |
joints | the best fittest IK solution. |
all_sols | a data structure to store all possible solutions. |
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.
njoint | index of joint indicate which joint is examined. |
rad | the value of joint will be check and update as output. |
void rb::kin::Artic::setLowLimit | ( | rb::math::VectorX & | low_lim | ) |
Set the lower limits of joint angles for the robot arm.
low_lim | An 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.
up_lim | An 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.
sols | a structure to storage all possible solutions of inverse kinematics. |
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.
th1_rad | angle (radian) of first joint. |
p0 | the position of wrist point wrt joint 0 (base) |
config | a vector of 3 bits to indicator 8 configuration (solutions) of robot arm. |
all_sols |
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.
th1_rad | angle (radian) of first joint. |
config | a vector of 3 bits to indicator 8 configuration (solutions) of robot arm. |
flange_tr | a H.T. Matrix of robot flange with respect to it base. |
all_sols | a structure to storage all possible solutions of inverse kinematics. |
|
protected |
|
protected |
|
protected |
|
protected |
Joint angle data member of modified D-H parameter for robot arm.
Joint angle (degree)