75 #ifndef UR_KINEMATICS_PLUGIN_
76 #define UR_KINEMATICS_PLUGIN_
83 #include <boost/shared_ptr.hpp>
86 #include <geometry_msgs/PoseStamped.h>
87 #include <moveit_msgs/GetPositionFK.h>
88 #include <moveit_msgs/GetPositionIK.h>
89 #include <moveit_msgs/KinematicSolverInfo.h>
90 #include <moveit_msgs/MoveItErrorCodes.h>
93 #include <kdl/jntarray.hpp>
94 #include <kdl/chainiksolvervel_pinv.hpp>
95 #include <kdl/chainiksolverpos_nr_jl.hpp>
96 #include <kdl/chainfksolverpos_recursive.hpp>
118 virtual bool getPositionIK(
const geometry_msgs::Pose &ik_pose,
119 const std::vector<double> &ik_seed_state,
120 std::vector<double> &solution,
121 moveit_msgs::MoveItErrorCodes &error_code,
125 const std::vector<double> &ik_seed_state,
127 std::vector<double> &solution,
128 moveit_msgs::MoveItErrorCodes &error_code,
132 const std::vector<double> &ik_seed_state,
134 const std::vector<double> &consistency_limits,
135 std::vector<double> &solution,
136 moveit_msgs::MoveItErrorCodes &error_code,
140 const std::vector<double> &ik_seed_state,
142 std::vector<double> &solution,
144 moveit_msgs::MoveItErrorCodes &error_code,
148 const std::vector<double> &ik_seed_state,
150 const std::vector<double> &consistency_limits,
151 std::vector<double> &solution,
153 moveit_msgs::MoveItErrorCodes &error_code,
156 virtual bool getPositionFK(
const std::vector<std::string> &link_names,
157 const std::vector<double> &joint_angles,
158 std::vector<geometry_msgs::Pose> &poses)
const;
161 const std::string& group_name,
162 const std::string& base_frame,
163 const std::vector<std::string>& tip_frames,
164 double search_discretization);
195 const std::vector<double> &ik_seed_state,
197 std::vector<double> &solution,
199 moveit_msgs::MoveItErrorCodes &error_code,
200 const std::vector<double> &consistency_limits,
203 virtual bool setRedundantJoints(
const std::vector<unsigned int> &redundant_joint_indices);
218 const std::vector<double> &consistency_limit,
219 const KDL::JntArray& solution)
const;
234 const std::vector<double> &consistency_limits,
235 KDL::JntArray &jnt_array,
236 bool lock_redundancy)
const;
264 std::vector<kdl_kinematics_plugin::JointMimic>
mimic_joints_;