modern_robotics
Functions
Chapter 6: Inverse Kinematics

Functions

const std::pair< const arma::vec, bool > mr::IKinBody (const std::vector< arma::vec6 > &Blist, const arma::mat44 &M, const arma::mat44 &T, const arma::vec &thetalist0, const double emog, const double ev)
 Computes inverse kinematics in the body frame for an open chain robot. More...
 
const std::pair< const arma::vec, bool > mr::IKinSpace (const std::vector< arma::vec6 > &Slist, const arma::mat44 &M, const arma::mat44 &T, const arma::vec &thetalist0, const double emog, const double ev)
 Computes inverse kinematics in the space frame for an open chain robot. More...
 

Detailed Description

Function Documentation

◆ IKinBody()

const std::pair< const arma::vec, bool > mr::IKinBody ( const std::vector< arma::vec6 > &  Blist,
const arma::mat44 &  M,
const arma::mat44 &  T,
const arma::vec &  thetalist0,
const double  emog,
const double  ev 
)

Computes inverse kinematics in the body frame for an open chain robot.

Parameters
BlistThe joint screw axes in the end-effector frame when the manipulator is at the home position, in the format of a matrix with axes as the columns
MThe home configuration of the end-effector
TThe desired end-effector configuration Tsd satisfying Tsd
thetalist0An initial guess of joint angles that are close to
emogA small positive tolerance on the end-effector orientation error. The returned joint angles must give an end-effector orientation error less than eomg
evA small positive tolerance on the end-effector linear position error. The returned joint angles must give an end-effector position error less than ev
Returns
thetalist: Joint angles that achieve T within the specified tolerances
success: A logical value where TRUE means that the function found a solution and FALSE means that it ran through the set number of maximum iterations without finding a solution within the tolerances eomg and ev.

Uses an iterative Newton-Raphson root-finding method. The maximum number of iterations before the algorithm is terminated has been hardcoded in as a variable called maxiterations. It is set to 20 at the start of the function, but can be changed if needed.

◆ IKinSpace()

const std::pair< const arma::vec, bool > mr::IKinSpace ( const std::vector< arma::vec6 > &  Slist,
const arma::mat44 &  M,
const arma::mat44 &  T,
const arma::vec &  thetalist0,
const double  emog,
const double  ev 
)

Computes inverse kinematics in the space frame for an open chain robot.

Parameters
SlistThe joint screw axes in the space frame when the manipulator is at the home position, in the format of a matrix with axes as the columns
MThe home configuration of the end-effector
TThe desired end-effector configuration Tsd
thetalist0An initial guess of joint angles that are close to satisfying Tsd
emogA small positive tolerance on the end-effector orientation error. The returned joint angles must give an end-effector orientation error less than eomg
evA small positive tolerance on the end-effector linear position error. The returned joint angles must give an end-effector position error less than ev
Returns
thetalist: Joint angles that achieve T within the specified tolerances.
success: A logical value where TRUE means that the function found a solution and FALSE means that it ran through the set number of maximum iterations without finding a solution within the tolerances eomg and ev.

Uses an iterative Newton-Raphson root-finding method. The maximum number of iterations before the algorithm is terminated has been hardcoded in as a variable called maxiterations. It is set to 20 at the start of the function, but can be changed if needed.