39 #include <kdl/config.h>
40 #include <kdl/frames.hpp>
41 #include <kdl/jntarray.hpp>
42 #include <kdl/tree.hpp>
46 #include <moveit_msgs/GetPositionFK.h>
47 #include <moveit_msgs/GetPositionIK.h>
48 #include <moveit_msgs/KinematicSolverInfo.h>
49 #include <moveit_msgs/MoveItErrorCodes.h>
51 #include <kdl/chainfksolverpos_recursive.hpp>
69 class PR2ArmIKSolver :
public KDL::ChainIkSolverPos
72 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
82 const std::string& tip_frame_name,
const double& search_discretization_angle,
const int& free_angle);
87 #define KDL_VERSION_LESS(a, b, c) ((KDL_VERSION) < ((a << 16) | (b << 8) | c))
88 #if KDL_VERSION_LESS(1, 4, 0)
93 #undef KDL_VERSION_LESS
105 int CartToJnt(
const KDL::JntArray& q_init,
const KDL::Frame& p_in, KDL::JntArray& q_out)
override;
107 int cartToJntSearch(
const KDL::JntArray& q_in,
const KDL::Frame& p_in, KDL::JntArray& q_out,
const double& timeout);
109 void getSolverInfo(moveit_msgs::KinematicSolverInfo& response)
115 bool getCount(
int& count,
const int& max_count,
const int& min_count);
126 void getKDLChainInfo(
const KDL::Chain& chain, moveit_msgs::KinematicSolverInfo& chain_info);
149 getPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
150 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
162 const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
163 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
175 const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
176 const std::vector<double>& consistency_limit, std::vector<double>& solution,
177 moveit_msgs::MoveItErrorCodes& error_code,
189 const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
190 std::vector<double>& solution,
const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
204 const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
205 const std::vector<double>& consistency_limit, std::vector<double>& solution,
206 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
213 bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
214 std::vector<geometry_msgs::Pose>& poses)
const override;
221 const std::string& base_frame,
const std::vector<std::string>& tip_frames,
222 double search_discretization)
override;
227 const std::vector<std::string>&
getJointNames()
const override;
232 const std::vector<std::string>&
getLinkNames()
const override;
248 moveit_msgs::MoveItErrorCodes& error_code)
const;
251 moveit_msgs::MoveItErrorCodes& error_code)
const;