A kinematics class for general serial links.
More...
#include <kinematic_chain.h>
|
|
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | KinematicChain () |
| | Default Constuctor.
|
| |
|
| KinematicChain (std::vector< std::unique_ptr< rb::kin::Link > > &links, rb::math::Matrix4 base=rb::math::Matrix4::Identity(), rb::math::Matrix4 tool=rb::math::Matrix4::Identity(), rb::math::Vector3 gravity=rb::math::Vector3(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.
|
| |
| 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.
|
| |
| 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.
|
| |
| bool | setTool (const ArmPose &tool_pose) |
| | Set the HT matrix of the offset b/w the arm flange and equipped tool or end-effector.
|
| |
| bool | getTool (ArmPose &tool_pose) const |
| | Get the HT matrix of the offset b/w the arm flange and equipped tool or end-effector.
|
| |
| void | setBase (const rb::math::Matrix4 &base) |
| | Set the Homogeneous Transformation matrix of the working base of the robot arm.
|
| |
| rb::math::Matrix4 | getBase (void) const |
| | Get the HT matrix of the working base of the robot arm.
|
| |
| rb::math::Matrix4 | getTCP (void) const |
| | Get the HT matrix of TCP w.r.t world coordination.
|
| |
| void | setDOF (void) |
| | Set the degree of freedom according to the property of links.
|
| |
| int | getDOF (void) const |
| | Get the degree of freedom of this kinematic chain.
|
| |
|
| std::vector< std::unique_ptr< rb::kin::Link > > | links_ |
| | A vector of Link class.
|
| |
|
std::vector< rb::math::Matrix4 > | frames_ |
| |
|
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.
|
| |
|
rb::math::Vector3 | gravity_ |
| | Gravity set as a vector.
|
| |
|
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 general serial links.
KinematicChain implement the kinematics of general serial links
◆ forwardKin()
Compute forward Kinematics for given angle, update each joint value, and return current current position and orientation of TCP.
- Parameters
-
| q | An array of joint value (degree or mm). |
| update | A 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.
◆ getBase()
◆ getDOF()
| int rb::kin::KinematicChain::getDOF |
( |
void |
| ) |
const |
Get the degree of freedom of this kinematic chain.
- Returns
◆ getTCP()
Get the HT matrix of TCP w.r.t world coordination.
- Returns
◆ getTool()
| 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
-
- Returns
- bool Check if setting success
◆ homoTrans()
| 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
-
| A | Given link length. |
| alpha | Given link twist. |
| D | Given link offset. |
| theta | Given joint angle. |
- Returns
- Homogeneous transformation matrix of given link properties.
-
Matrix4
◆ inverseKin()
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_tf | Transformation of tcp in world coordination. |
| joints | The best fittest solution. |
| all_sols | A data structure to store all possible solutions. |
Implemented in rb::kin::Artic.
◆ setBase()
Set the Homogeneous Transformation matrix of the working base of the robot arm.
- Parameters
-
| base | a Homogeneous Transformation matrix from World -> the robot base. |
- Returns
◆ setDOF()
| void rb::kin::KinematicChain::setDOF |
( |
void |
| ) |
|
Set the degree of freedom according to the property of links.
- Returns
◆ setTool()
| 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
-
- Returns
- Check if setting success
◆ links_
| std::vector<std::unique_ptr<rb::kin::Link> > rb::kin::KinematicChain::links_ |
|
protected |
A vector of Link class.
A vector of HT matrix to the pose of each joint and TCP.
The documentation for this class was generated from the following files: