modern_robotics
inverse_kinematics.hpp
Go to the documentation of this file.
1 #ifndef MODERN_ROBOTICS__INVERSE_KINEMATICS_HPP___
2 #define MODERN_ROBOTICS__INVERSE_KINEMATICS_HPP___
3 
4 #include <armadillo>
5 #include <vector>
6 #include <utility>
7 
8 namespace mr
9 {
11 
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,
40  const double emog,
41  const double ev
42 );
43 
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,
72  const double emog,
73  const double ev
74 );
75 }
76 
77 #endif
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