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);