00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef PR2_ARM_IK_NODE_H
00038 #define PR2_ARM_IK_NODE_H
00039
00040 #include <kdl/frames.hpp>
00041 #include <kdl/jntarray.hpp>
00042 #include <kdl/tree.hpp>
00043 #include <kdl_parser/kdl_parser.hpp>
00044
00045 #include <angles/angles.h>
00046 #include <tf_conversions/tf_kdl.h>
00047
00048 #include <moveit/macros/class_forward.h>
00049 #include <moveit_msgs/GetPositionFK.h>
00050 #include <moveit_msgs/GetPositionIK.h>
00051 #include <moveit_msgs/GetKinematicSolverInfo.h>
00052 #include <moveit_msgs/MoveItErrorCodes.h>
00053
00054 #include <kdl/chainfksolverpos_recursive.hpp>
00055
00056 #include <boost/shared_ptr.hpp>
00057
00058 #include <moveit/kinematics_base/kinematics_base.h>
00059
00060 #include "pr2_arm_ik.h"
00061
00062 namespace pr2_arm_kinematics
00063 {
00064 static const int NO_IK_SOLUTION = -1;
00065 static const int TIMED_OUT = -2;
00066
00067 MOVEIT_CLASS_FORWARD(PR2ArmIKSolver);
00068
00069
00070 class PR2ArmIKSolver : public KDL::ChainIkSolverPos
00071 {
00072 public:
00073 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00074
00083 PR2ArmIKSolver(const urdf::ModelInterface& robot_model, const std::string& root_frame_name,
00084 const std::string& tip_frame_name, const double& search_discretization_angle, const int& free_angle);
00085
00086 ~PR2ArmIKSolver(){};
00087
00091 PR2ArmIK pr2_arm_ik_;
00092
00096 bool active_;
00097
00098 int CartToJnt(const KDL::JntArray& q_init, const KDL::Frame& p_in, KDL::JntArray& q_out);
00099
00100 int CartToJntSearch(const KDL::JntArray& q_in, const KDL::Frame& p_in, KDL::JntArray& q_out, const double& timeout);
00101
00102 void getSolverInfo(moveit_msgs::KinematicSolverInfo& response)
00103 {
00104 pr2_arm_ik_.getSolverInfo(response);
00105 }
00106
00107 private:
00108 bool getCount(int& count, const int& max_count, const int& min_count);
00109
00110 double search_discretization_angle_;
00111
00112 int free_angle_;
00113
00114 std::string root_frame_name_;
00115 };
00116
00117 Eigen::Matrix4f KDLToEigenMatrix(const KDL::Frame& p);
00118 double computeEuclideanDistance(const std::vector<double>& array_1, const KDL::JntArray& array_2);
00119 void getKDLChainInfo(const KDL::Chain& chain, moveit_msgs::KinematicSolverInfo& chain_info);
00120
00121 MOVEIT_CLASS_FORWARD(PR2ArmKinematicsPlugin);
00122
00123 class PR2ArmKinematicsPlugin : public kinematics::KinematicsBase
00124 {
00125 public:
00129 PR2ArmKinematicsPlugin();
00130
00131 void setRobotModel(boost::shared_ptr<urdf::ModelInterface>& robot_model);
00132
00137 bool isActive();
00138
00146 virtual bool
00147 getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
00148 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
00149 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00150
00159 virtual bool
00160 searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00161 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
00162 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00172 virtual bool
00173 searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00174 const std::vector<double>& consistency_limits, std::vector<double>& solution,
00175 moveit_msgs::MoveItErrorCodes& error_code,
00176 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00177
00186 virtual bool searchPositionIK(
00187 const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00188 std::vector<double>& solution, const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
00189 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00190
00201 virtual bool
00202 searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00203 const std::vector<double>& consistency_limits, std::vector<double>& solution,
00204 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
00205 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00206
00214 virtual bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
00215 std::vector<geometry_msgs::Pose>& poses) const;
00216
00221 virtual bool initialize(const std::string& robot_description, const std::string& group_name,
00222 const std::string& base_name, const std::string& tip_name, double search_discretization);
00223
00227 const std::vector<std::string>& getJointNames() const;
00228
00232 const std::vector<std::string>& getLinkNames() const;
00233
00234 protected:
00235 bool active_;
00236 int free_angle_;
00237 boost::shared_ptr<urdf::ModelInterface> robot_model_;
00238 pr2_arm_kinematics::PR2ArmIKSolverPtr pr2_arm_ik_solver_;
00239 std::string root_name_;
00240 int dimension_;
00241 boost::shared_ptr<KDL::ChainFkSolverPos_recursive> jnt_to_pose_solver_;
00242 KDL::Chain kdl_chain_;
00243 moveit_msgs::KinematicSolverInfo ik_solver_info_, fk_solver_info_;
00244
00245 mutable IKCallbackFn desiredPoseCallback_;
00246 mutable IKCallbackFn solutionCallback_;
00247
00248 void desiredPoseCallback(const KDL::JntArray& jnt_array, const KDL::Frame& ik_pose,
00249 moveit_msgs::MoveItErrorCodes& error_code) const;
00250
00251 void jointSolutionCallback(const KDL::JntArray& jnt_array, const KDL::Frame& ik_pose,
00252 moveit_msgs::MoveItErrorCodes& error_code) const;
00253 };
00254 }
00255
00256 #endif