37 #ifndef MOVEIT_PR2_ARM_IK_SOLVER_ 38 #define MOVEIT_PR2_ARM_IK_SOLVER_ 42 #include <kdl/chainiksolver.hpp> 46 #include <moveit_msgs/PositionIKRequest.h> 47 #include <geometry_msgs/PoseStamped.h> 66 const std::string &root_frame_name,
67 const std::string &tip_frame_name,
68 const double &search_discretization_angle,
69 const int &free_angle);
73 virtual void updateInternalDataStructures();
115 std::vector<KDL::JntArray> &q_out);
130 std::vector<KDL::JntArray> &q_out,
131 const double &timeout);
169 const double &timeout,
170 const double& consistency_limit);
188 const double &timeout,
189 moveit_msgs::MoveItErrorCodes &error_code,
209 const double &timeout,
210 const double& consistency_limit,
211 moveit_msgs::MoveItErrorCodes &error_code,
221 std::string getFrameId();
223 unsigned int getFreeAngle()
const {
227 void setFreeAngle(
const unsigned int& free_angle) {
251 const double &timeout,
252 bool use_consistency_limit,
253 const double& consistency_limit,
254 moveit_msgs::MoveItErrorCodes &error_code,
257 bool getCount(
int &count,
const int &max_count,
const int &min_count);
266 #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
const std::string response