Class TRAC_IK

Class Documentation

class TRAC_IK

Public Functions

TRAC_IK(rclcpp::Node::SharedPtr nh, const KDL::Chain &_chain, const KDL::JntArray &_q_min, const KDL::JntArray &_q_max, double _maxtime = 0.005, double _eps = 1e-5, SolveType _type = Speed)
TRAC_IK(rclcpp::Node::SharedPtr nh, const std::string &base_link, const std::string &tip_link, const std::string &URDF_param = "robot_description", double _maxtime = 0.005, double _eps = 1e-5, SolveType _type = Speed)
~TRAC_IK()
inline bool getKDLChain(KDL::Chain &chain_)
inline bool getKDLLimits(KDL::JntArray &lb_, KDL::JntArray &ub_)
inline bool getSolutions(std::vector<KDL::JntArray> &solutions_)
inline bool getSolutions(std::vector<KDL::JntArray> &solutions_, std::vector<std::pair<double, uint>> &errors_)
inline bool setKDLLimits(KDL::JntArray &lb_, KDL::JntArray &ub_)
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist &bounds = KDL::Twist::Zero())
inline void SetSolveType(SolveType _type)

Public Static Functions

static inline double JointErr(const KDL::JntArray &arr1, const KDL::JntArray &arr2)