37 #ifndef PR2_ARM_IK_NODE_H 38 #define PR2_ARM_IK_NODE_H 40 #include <kdl/frames.hpp> 41 #include <kdl/jntarray.hpp> 42 #include <kdl/tree.hpp> 45 #include <angles/angles.h> 46 #include <tf_conversions/tf_kdl.h> 49 #include <moveit_msgs/GetPositionFK.h> 50 #include <moveit_msgs/GetPositionIK.h> 51 #include <moveit_msgs/KinematicSolverInfo.h> 52 #include <moveit_msgs/MoveItErrorCodes.h> 54 #include <kdl/chainfksolverpos_recursive.hpp> 86 const std::string& tip_frame_name,
const double& search_discretization_angle,
const int& free_angle);
110 bool getCount(
int& count,
const int& max_count,
const int& min_count);
133 void setRobotModel(urdf::ModelInterfaceSharedPtr&
robot_model);
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 searchPositionIK(
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 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
176 const std::vector<double>& consistency_limits, std::vector<double>& solution,
177 moveit_msgs::MoveItErrorCodes& error_code,
189 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
190 std::vector<double>& solution,
const IKCallbackFn& solution_callback,
191 moveit_msgs::MoveItErrorCodes& error_code,
205 searchPositionIK(
const geometry_msgs::Pose& ik_pose,
const std::vector<double>& ik_seed_state,
double timeout,
206 const std::vector<double>& consistency_limits, std::vector<double>& solution,
207 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
217 virtual bool getPositionFK(
const std::vector<std::string>& link_names,
const std::vector<double>& joint_angles,
218 std::vector<geometry_msgs::Pose>& poses)
const;
224 virtual bool initialize(
const std::string& robot_description,
const std::string& group_name,
225 const std::string& base_name,
const std::string& tip_name,
double search_discretization);
230 const std::vector<std::string>& getJointNames()
const;
235 const std::vector<std::string>& getLinkNames()
const;
252 moveit_msgs::MoveItErrorCodes& error_code)
const;
255 moveit_msgs::MoveItErrorCodes& error_code)
const;
double search_discretization_angle_
A set of options for the kinematics solver.
Core components of MoveIt!
IKCallbackFn desiredPoseCallback_
MOVEIT_CLASS_FORWARD(PR2ArmIKSolver)
ROSCONSOLE_DECL void initialize()
pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_ik_solver_
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
std::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info)
Provides an interface for kinematics solvers.
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out)
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
PR2ArmIK pr2_arm_ik_
The PR2 inverse kinematics solver.
urdf::ModelInterfaceSharedPtr robot_model_
Eigen::Affine3f KDLToEigenMatrix(const KDL::Frame &p)
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
The signature for a callback that can compute IK.
moveit_msgs::KinematicSolverInfo ik_solver_info_
void getSolverInfo(moveit_msgs::KinematicSolverInfo &info)
get chain information about the arm. This populates the IK query response, filling in joint level inf...
IKCallbackFn solutionCallback_
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
double computeEuclideanDistance(const std::vector< double > &array_1, const KDL::JntArray &array_2)