1 #ifndef MODERN_ROBOTICS__INVERSE_KINEMATICS_HPP___
2 #define MODERN_ROBOTICS__INVERSE_KINEMATICS_HPP___
35 const std::pair<const arma::vec, bool>
IKinBody(
36 const std::vector<arma::vec6> & Blist,
37 const arma::mat44 & M,
38 const arma::mat44 & T,
39 const arma::vec & thetalist0,
67 const std::pair<const arma::vec, bool>
IKinSpace(
68 const std::vector<arma::vec6> & Slist,
69 const arma::mat44 & M,
70 const arma::mat44 & T,
71 const arma::vec & thetalist0,
const std::pair< const arma::vec, bool > 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.
Definition: inverse_kinematics.cpp:10
const std::pair< const arma::vec, bool > 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.
Definition: inverse_kinematics.cpp:40
Definition: dynamics_of_open_chains.hpp:7