Go to the documentation of this file.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 <ros/ros.h>
00041 #include <tf/tf.h>
00042 #include <tf/transform_listener.h>
00043
00044 #include <angles/angles.h>
00045 #include <pr2_arm_kinematics/pr2_arm_ik_solver.h>
00046 #include <tf_conversions/tf_kdl.h>
00047
00048 #include <moveit_msgs/GetPositionFK.h>
00049 #include <moveit_msgs/GetPositionIK.h>
00050 #include <moveit_msgs/GetKinematicSolverInfo.h>
00051 #include <moveit_msgs/MoveItErrorCodes.h>
00052
00053 #include <kdl/chainfksolverpos_recursive.hpp>
00054
00055 #include <boost/shared_ptr.hpp>
00056
00057 #include <moveit/kinematics_base/kinematics_base.h>
00058
00060 namespace pr2_arm_kinematics
00061 {
00062 class PR2ArmKinematicsPlugin : public kinematics::KinematicsBase
00063 {
00064 public:
00065
00069 PR2ArmKinematicsPlugin();
00070
00075 bool isActive();
00076
00077 virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose,
00078 const std::vector<double> &ik_seed_state,
00079 std::vector<double> &solution,
00080 moveit_msgs::MoveItErrorCodes &error_code,
00081 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00082
00083 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00084 const std::vector<double> &ik_seed_state,
00085 double timeout,
00086 std::vector<double> &solution,
00087 moveit_msgs::MoveItErrorCodes &error_code,
00088 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00089
00090 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00091 const std::vector<double> &ik_seed_state,
00092 double timeout,
00093 const std::vector<double> &consistency_limits,
00094 std::vector<double> &solution,
00095 moveit_msgs::MoveItErrorCodes &error_code,
00096 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00097
00098 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00099 const std::vector<double> &ik_seed_state,
00100 double timeout,
00101 std::vector<double> &solution,
00102 const IKCallbackFn &solution_callback,
00103 moveit_msgs::MoveItErrorCodes &error_code,
00104 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00105
00106 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00107 const std::vector<double> &ik_seed_state,
00108 double timeout,
00109 const std::vector<double> &consistency_limits,
00110 std::vector<double> &solution,
00111 const IKCallbackFn &solution_callback,
00112 moveit_msgs::MoveItErrorCodes &error_code,
00113 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00114
00115 virtual bool getPositionFK(const std::vector<std::string> &link_names,
00116 const std::vector<double> &joint_angles,
00117 std::vector<geometry_msgs::Pose> &poses) const;
00118
00123 virtual bool initialize(const std::string& robot_description,
00124 const std::string& group_name,
00125 const std::string& base_frame,
00126 const std::string& tip_frame,
00127 double search_discretization);
00128
00132 const std::vector<std::string>& getJointNames() const;
00133
00137 const std::vector<std::string>& getLinkNames() const;
00138
00139 protected:
00140
00141 bool active_;
00142 int free_angle_;
00143 urdf::Model robot_model_;
00144 ros::NodeHandle node_handle_, root_handle_;
00145 boost::shared_ptr<pr2_arm_kinematics::PR2ArmIKSolver> pr2_arm_ik_solver_;
00146 ros::ServiceServer ik_service_,fk_service_,ik_solver_info_service_,fk_solver_info_service_;
00147
00148 std::string root_name_;
00149 int dimension_;
00150 boost::shared_ptr<KDL::ChainFkSolverPos_recursive> jnt_to_pose_solver_;
00151 KDL::Chain kdl_chain_;
00152 moveit_msgs::KinematicSolverInfo ik_solver_info_, fk_solver_info_;
00153
00154 };
00155 }
00156
00157 #endif