31 #ifndef TRAC_IK_KINEMATICS_PLUGIN_ 32 #define TRAC_IK_KINEMATICS_PLUGIN_ 35 #include <kdl/chain.hpp> 86 const std::vector<double> &ik_seed_state,
87 std::vector<double> &solution,
88 moveit_msgs::MoveItErrorCodes &error_code,
100 const std::vector<double> &ik_seed_state,
102 std::vector<double> &solution,
103 moveit_msgs::MoveItErrorCodes &error_code,
116 const std::vector<double> &ik_seed_state,
118 const std::vector<double> &consistency_limits,
119 std::vector<double> &solution,
120 moveit_msgs::MoveItErrorCodes &error_code,
132 const std::vector<double> &ik_seed_state,
134 std::vector<double> &solution,
136 moveit_msgs::MoveItErrorCodes &error_code,
150 const std::vector<double> &ik_seed_state,
152 const std::vector<double> &consistency_limits,
153 std::vector<double> &solution,
155 moveit_msgs::MoveItErrorCodes &error_code,
159 const std::vector<double> &ik_seed_state,
161 std::vector<double> &solution,
163 moveit_msgs::MoveItErrorCodes &error_code,
164 const std::vector<double> &consistency_limits,
179 bool getPositionFK(
const std::vector<std::string> &link_names,
180 const std::vector<double> &joint_angles,
181 std::vector<geometry_msgs::Pose> &poses)
const;
184 bool initialize(
const std::string &robot_description,
185 const std::string& group_name,
186 const std::string& base_name,
187 const std::string& tip_name,
188 double search_discretization);
std::vector< std::string > link_names_
bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
Given a desired pose of the end-effector, compute the joint angles to reach it.
const std::vector< std::string > & getJointNames() const
TRAC_IKKinematicsPlugin()
bool initialize(const std::string &robot_description, const std::string &group_name, const std::string &base_name, const std::string &tip_name, double search_discretization)
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
const std::vector< std::string > & getLinkNames() const
int getKDLSegmentIndex(const std::string &name) const
~TRAC_IKKinematicsPlugin()
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const
Given a set of joint angles and a set of links, compute their pose.
bool searchPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const
Given a desired pose of the end-effector, search for the joint angles required to reach it...
std::vector< std::string > joint_names_