37 #ifndef MOVEIT_PR2_ARM_IK_SOLVER_ 38 #define MOVEIT_PR2_ARM_IK_SOLVER_ 42 #include <kdl/chainiksolver.hpp> 46 #include <moveit_msgs/KinematicSolverInfo.h> 47 #include <moveit_msgs/PositionIKRequest.h> 48 #include <geometry_msgs/PoseStamped.h> 67 const std::string &root_frame_name,
68 const std::string &tip_frame_name,
69 const double &search_discretization_angle,
70 const int &free_angle);
114 std::vector<KDL::JntArray> &q_out);
129 std::vector<KDL::JntArray> &q_out,
130 const double &timeout);
146 const double &timeout);
165 const double &timeout,
166 const double& consistency_limit);
184 const double &timeout,
185 moveit_msgs::MoveItErrorCodes &error_code,
205 const double &timeout,
206 const double& consistency_limit,
207 moveit_msgs::MoveItErrorCodes &error_code,
215 void getSolverInfo(moveit_msgs::KinematicSolverInfo &response);
217 std::string getFrameId();
219 unsigned int getFreeAngle()
const {
223 void setFreeAngle(
const unsigned int& free_angle) {
247 const double &timeout,
248 bool use_consistency_limit,
249 const double& consistency_limit,
250 moveit_msgs::MoveItErrorCodes &error_code,
253 bool getCount(
int &count,
const int &max_count,
const int &min_count);
262 #endif// PR2_ARM_IK_SOLVER_H double search_discretization_angle_
Namespace for the PR2ArmKinematics.
bool getCount(int &count, const int &max_count, const int &min_count)
int CartToJntSearch(const KDL::JntArray &q_in, const KDL::Frame &p_in, KDL::JntArray &q_out, const double &timeout)
std::string root_frame_name_
static const int NO_IK_SOLUTION
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out)
bool active_
Indicates whether the solver has been successfully initialized.
boost::function< void(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn
PR2ArmIKSolver(const urdf::ModelInterface &robot_model, const std::string &root_frame_name, const std::string &tip_frame_name, const double &search_discretization_angle, const int &free_angle)
void getSolverInfo(moveit_msgs::KinematicSolverInfo &response)
static const int TIMED_OUT