|
modern_robotics
|
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... | |
| 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.
| Blist | The 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 |
| M | The home configuration of the end-effector |
| T | The desired end-effector configuration Tsd satisfying Tsd |
| thetalist0 | An initial guess of joint angles that are close to |
| emog | A small positive tolerance on the end-effector orientation error. The returned joint angles must give an end-effector orientation error less than eomg |
| ev | A small positive tolerance on the end-effector linear position error. The returned joint angles must give an end-effector position error less than 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.
| 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.
| Slist | The 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 |
| M | The home configuration of the end-effector |
| T | The desired end-effector configuration Tsd |
| thetalist0 | An initial guess of joint angles that are close to satisfying Tsd |
| emog | A small positive tolerance on the end-effector orientation error. The returned joint angles must give an end-effector orientation error less than eomg |
| ev | A small positive tolerance on the end-effector linear position error. The returned joint angles must give an end-effector position error less than 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.