Class TRAC_IK
Defined in File trac_ik.hpp
Class Documentation
-
class TRAC_IK
Public Functions
-
TRAC_IK(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, const rclcpp::Logger &logger = rclcpp::get_logger("trac_ik.trac_ik_lib"))
-
~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())
Public Static Functions
-
static inline double JointErr(const KDL::JntArray &arr1, const KDL::JntArray &arr2)
-
TRAC_IK(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, const rclcpp::Logger &logger = rclcpp::get_logger("trac_ik.trac_ik_lib"))