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 #ifndef TRAC_IK_KINEMATICS_PLUGIN_
00032 #define TRAC_IK_KINEMATICS_PLUGIN_
00033
00034 #include <moveit/kinematics_base/kinematics_base.h>
00035 #include <kdl/chain.hpp>
00036
00037 namespace trac_ik_kinematics_plugin
00038 {
00039
00040 class TRAC_IKKinematicsPlugin : public kinematics::KinematicsBase
00041 {
00042 std::vector<std::string> joint_names_;
00043 std::vector<std::string> link_names_;
00044
00045 uint num_joints_;
00046 bool active_;
00047
00048 KDL::Chain chain;
00049 bool position_ik_;
00050
00051 KDL::JntArray joint_min, joint_max;
00052
00053 std::string solve_type;
00054
00055 public:
00056 const std::vector<std::string>& getJointNames() const { return joint_names_; }
00057 const std::vector<std::string>& getLinkNames() const { return link_names_; }
00058
00059
00063 TRAC_IKKinematicsPlugin(): active_(false), position_ik_(false){}
00064
00065 ~TRAC_IKKinematicsPlugin() {
00066 }
00067
00077
00078 bool getPositionIK(const geometry_msgs::Pose &ik_pose,
00079 const std::vector<double> &ik_seed_state,
00080 std::vector<double> &solution,
00081 moveit_msgs::MoveItErrorCodes &error_code,
00082 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00083
00092 bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00093 const std::vector<double> &ik_seed_state,
00094 double timeout,
00095 std::vector<double> &solution,
00096 moveit_msgs::MoveItErrorCodes &error_code,
00097 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00098
00108 bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00109 const std::vector<double> &ik_seed_state,
00110 double timeout,
00111 const std::vector<double> &consistency_limits,
00112 std::vector<double> &solution,
00113 moveit_msgs::MoveItErrorCodes &error_code,
00114 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00115
00124 bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00125 const std::vector<double> &ik_seed_state,
00126 double timeout,
00127 std::vector<double> &solution,
00128 const IKCallbackFn &solution_callback,
00129 moveit_msgs::MoveItErrorCodes &error_code,
00130 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00131
00142 bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00143 const std::vector<double> &ik_seed_state,
00144 double timeout,
00145 const std::vector<double> &consistency_limits,
00146 std::vector<double> &solution,
00147 const IKCallbackFn &solution_callback,
00148 moveit_msgs::MoveItErrorCodes &error_code,
00149 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00150
00151 bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00152 const std::vector<double> &ik_seed_state,
00153 double timeout,
00154 std::vector<double> &solution,
00155 const IKCallbackFn &solution_callback,
00156 moveit_msgs::MoveItErrorCodes &error_code,
00157 const std::vector<double> &consistency_limits,
00158 const kinematics::KinematicsQueryOptions &options) const;
00159
00160
00172 bool getPositionFK(const std::vector<std::string> &link_names,
00173 const std::vector<double> &joint_angles,
00174 std::vector<geometry_msgs::Pose> &poses) const;
00175
00176
00177 bool initialize(const std::string &robot_description,
00178 const std::string& group_name,
00179 const std::string& base_name,
00180 const std::string& tip_name,
00181 double search_discretization);
00182
00183 private:
00184
00185 int getKDLSegmentIndex(const std::string &name) const;
00186
00187 };
00188 }
00189
00190 #endif