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 KINEMATICS_BASE_
00038 #define KINEMATICS_BASE_
00039
00040 #include <geometry_msgs/PoseStamped.h>
00041 #include <arm_navigation_msgs/RobotState.h>
00042 #include <boost/function.hpp>
00043
00044 namespace kinematics {
00045
00046 static const int SUCCESS = 1;
00047 static const int TIMED_OUT = -1;
00048 static const int NO_IK_SOLUTION = -2;
00049 static const int FRAME_TRANSFORM_FAILURE = -3;
00050 static const int IK_LINK_INVALID = -4;
00051 static const int IK_LINK_IN_COLLISION = -5;
00052 static const int STATE_IN_COLLISION = -6;
00053 static const int INVALID_LINK_NAME = -7;
00054 static const int GOAL_CONSTRAINTS_VIOLATED = -7;
00055 static const int INACTIVE = -8;
00056
00061 class KinematicsBase {
00062 public:
00070 virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose,
00071 const std::vector<double> &ik_seed_state,
00072 std::vector<double> &solution,
00073 int &error_code) = 0;
00074
00083 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00084 const std::vector<double> &ik_seed_state,
00085 const double &timeout,
00086 std::vector<double> &solution,
00087 int &error_code) = 0;
00088
00098 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00099 const std::vector<double> &ik_seed_state,
00100 const double &timeout,
00101 const unsigned int& redundancy,
00102 const double &consistency_limit,
00103 std::vector<double> &solution,
00104 int &error_code) = 0;
00105
00114 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00115 const std::vector<double> &ik_seed_state,
00116 const double &timeout,
00117 std::vector<double> &solution,
00118 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &desired_pose_callback,
00119 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &solution_callback,
00120 int &error_code) = 0;
00121
00132 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00133 const std::vector<double> &ik_seed_state,
00134 const double &timeout,
00135 const unsigned int& redundancy,
00136 const double &consistency_limit,
00137 std::vector<double> &solution,
00138 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &desired_pose_callback,
00139 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &solution_callback,
00140 int &error_code) = 0;
00141
00142
00149 virtual bool getPositionFK(const std::vector<std::string> &link_names,
00150 const std::vector<double> &joint_angles,
00151 std::vector<geometry_msgs::Pose> &poses) = 0;
00152
00157 virtual void setValues(const std::string& group_name,
00158 const std::string& base_name,
00159 const std::string& tip_name,
00160 const double& search_discretization) {
00161 group_name_ = group_name;
00162 base_name_ = base_name;
00163 tip_name_ = tip_name;
00164 search_discretization_ = search_discretization;
00165 }
00166
00167 virtual bool initialize(const std::string& group_name,
00168 const std::string& base_name,
00169 const std::string& tip_name,
00170 const double& search_discretization) = 0;
00171
00176 virtual const std::string& getGroupName() const {
00177 return group_name_;
00178 }
00179
00180 virtual const std::string& getBaseName() const {
00181 return base_name_;
00182 }
00183
00187 virtual const std::string& getTipName() const {
00188 return tip_name_;
00189 }
00190
00194 virtual const std::vector<std::string>& getJointNames() const = 0;
00195
00199 virtual const std::vector<std::string>& getLinkNames() const = 0;
00200
00204 virtual ~KinematicsBase(){}
00205
00206 void setSearchDiscretization(double sd) {
00207 search_discretization_ = sd;
00208 }
00209
00210 double getSearchDiscretization() const {
00211 return search_discretization_;
00212 }
00213
00214 protected:
00215 std::string group_name_;
00216 std::string base_name_;
00217 std::string tip_name_;
00218 double search_discretization_;
00219 KinematicsBase(){}
00220 };
00221 };
00222
00223 #endif