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> 66 const double& search_discretization_angle,
const int& free_angle);
127 const double& timeout);
158 const double& consistency_limit);
174 moveit_msgs::MoveItErrorCodes& error_code,
192 const double& consistency_limit, moveit_msgs::MoveItErrorCodes& error_code,
202 std::string getFrameId();
204 unsigned int getFreeAngle()
const 209 void setFreeAngle(
const unsigned int& free_angle)
231 bool use_consistency_limit,
const double& consistency_limit,
232 moveit_msgs::MoveItErrorCodes& error_code,
235 bool getCount(
int& count,
const int& max_count,
const int& min_count);
244 #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)
std::string root_frame_name_
static const int NO_IK_SOLUTION
void updateInternalDataStructures()
~PR2ArmIKSolver() override
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
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out) override
const std::string response