Class NLOPT_IK
Defined in File nlopt_ik.hpp
Class Documentation
-
class NLOPT_IK
Public Functions
-
NLOPT_IK(const KDL::Chain &_chain, const KDL::JntArray &_q_min, const KDL::JntArray &_q_max, double _maxtime = 0.005, double _eps = 1e-3, OptType _type = SumSq, const rclcpp::Logger &_logger = rclcpp::get_logger("trac_ik.trac_ik_lib"))
-
inline ~NLOPT_IK()
-
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out, const KDL::Twist bounds = KDL::Twist::Zero(), const KDL::JntArray &q_desired = KDL::JntArray())
-
double minJoints(const std::vector<double> &x, std::vector<double> &grad)
-
void cartSumSquaredError(const std::vector<double> &x, double error[])
-
void cartDQError(const std::vector<double> &x, double error[])
-
void cartL2NormError(const std::vector<double> &x, double error[])
-
inline void setMaxtime(double t)
Friends
- friend class TRAC_IK::TRAC_IK
-
NLOPT_IK(const KDL::Chain &_chain, const KDL::JntArray &_q_min, const KDL::JntArray &_q_max, double _maxtime = 0.005, double _eps = 1e-3, OptType _type = SumSq, const rclcpp::Logger &_logger = rclcpp::get_logger("trac_ik.trac_ik_lib"))