Go to the documentation of this file.
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;
bool getPositionFK(const std::vector< std::string > &link_names, const std::vector< double > &joint_angles, std::vector< geometry_msgs::Pose > &poses) const override
Given a set of joint angles and a set of links, compute their pose.
Core components of MoveIt.
moveit_msgs::KinematicSolverInfo fk_solver_info_
static const int TIMED_OUT
void getSolverInfo(moveit_msgs::KinematicSolverInfo &response)
bool getCount(int &count, const int &max_count, const int &min_count)
bool getPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
Given a desired pose of the end-effector, compute the joint angles to reach it.
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
void getKDLChainInfo(const KDL::Chain &chain, moveit_msgs::KinematicSolverInfo &chain_info)
bool isActive()
Specifies if the node is active or not.
boost::function< void(const geometry_msgs::Pose &, const std::vector< double > &, moveit_msgs::MoveItErrorCodes &)> IKCallbackFn
Signature for a callback to validate an IK solution. Typically used for collision checking.
int CartToJnt(const KDL::JntArray &q_init, const KDL::Frame &p_in, KDL::JntArray &q_out) override
const std::vector< std::string > & getLinkNames() const override
Return all the link names in the order they are represented internally.
const std::vector< std::string > & getJointNames() const override
Return all the joint names in the order they are used internally.
IKCallbackFn solutionCallback_
IKCallbackFn desiredPoseCallback_
void getSolverInfo(moveit_msgs::KinematicSolverInfo &info)
get chain information about the arm. This populates the IK query response, filling in joint level inf...
bool initialize(const moveit::core::RobotModel &robot_model, const std::string &group_name, const std::string &base_frame, const std::vector< std::string > &tip_frames, double search_discretization) override
Initialization function for the kinematics.
Provides an interface for kinematics solvers.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW 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)
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_ik_solver_
double computeEuclideanDistance(const std::vector< double > &array_1, const KDL::JntArray &array_2)
MOVEIT_CLASS_FORWARD(PR2ArmIKSolver)
std::shared_ptr< KDL::ChainFkSolverPos_recursive > jnt_to_pose_solver_
static const int NO_IK_SOLUTION
Eigen::Isometry3f KDLToEigenMatrix(const KDL::Frame &p)
std::string root_frame_name_
PR2ArmKinematicsPlugin()
Plugin-able interface to the PR2 arm kinematics.
int cartToJntSearch(const KDL::JntArray &q_in, const KDL::Frame &p_in, KDL::JntArray &q_out, const double &timeout)
A set of options for the kinematics solver.
void updateInternalDataStructures()
void desiredPoseCallback(const KDL::JntArray &jnt_array, const KDL::Frame &ik_pose, moveit_msgs::MoveItErrorCodes &error_code) const
void jointSolutionCallback(const KDL::JntArray &jnt_array, const KDL::Frame &ik_pose, moveit_msgs::MoveItErrorCodes &error_code) const
bool active_
Indicates whether the solver has been successfully initialized.
PR2ArmIK pr2_arm_ik_
The PR2 inverse kinematics solver.
moveit_msgs::KinematicSolverInfo ik_solver_info_
bool searchPositionIK(const geometry_msgs::Pose &ik_pose, const std::vector< double > &ik_seed_state, double timeout, std::vector< double > &solution, moveit_msgs::MoveItErrorCodes &error_code, const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions()) const override
Given a desired pose of the end-effector, search for the joint angles required to reach it....
double search_discretization_angle_
~PR2ArmIKSolver() override
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Thu Nov 21 2024 03:23:41