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 MOVEIT_KINEMATICS_BASE_KINEMATICS_BASE_
00038 #define MOVEIT_KINEMATICS_BASE_KINEMATICS_BASE_
00039
00040 #include <geometry_msgs/PoseStamped.h>
00041 #include <moveit_msgs/MoveItErrorCodes.h>
00042 #include <boost/function.hpp>
00043 #include <console_bridge/console.h>
00044 #include <string>
00045
00046 namespace moveit
00047 {
00048 namespace core
00049 {
00050 class JointModelGroup;
00051 class RobotState;
00052 }
00053 }
00054
00056 namespace kinematics
00057 {
00058
00063 struct KinematicsQueryOptions
00064 {
00065 KinematicsQueryOptions() :
00066 lock_redundant_joints(false),
00067 return_approximate_solution(false)
00068 {
00069 }
00070
00071 bool lock_redundant_joints;
00072 bool return_approximate_solution;
00073 };
00074
00075
00080 class KinematicsBase
00081 {
00082 public:
00083
00084 static const double DEFAULT_SEARCH_DISCRETIZATION;
00085 static const double DEFAULT_TIMEOUT;
00086
00088 typedef boost::function<void(const geometry_msgs::Pose &ik_pose, const std::vector<double> &ik_solution, moveit_msgs::MoveItErrorCodes &error_code)> IKCallbackFn;
00089
00099 virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose,
00100 const std::vector<double> &ik_seed_state,
00101 std::vector<double> &solution,
00102 moveit_msgs::MoveItErrorCodes &error_code,
00103 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const = 0;
00104
00117 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00118 const std::vector<double> &ik_seed_state,
00119 double timeout,
00120 std::vector<double> &solution,
00121 moveit_msgs::MoveItErrorCodes &error_code,
00122 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const = 0;
00123
00137 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00138 const std::vector<double> &ik_seed_state,
00139 double timeout,
00140 const std::vector<double> &consistency_limits,
00141 std::vector<double> &solution,
00142 moveit_msgs::MoveItErrorCodes &error_code,
00143 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const = 0;
00144
00158 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00159 const std::vector<double> &ik_seed_state,
00160 double timeout,
00161 std::vector<double> &solution,
00162 const IKCallbackFn &solution_callback,
00163 moveit_msgs::MoveItErrorCodes &error_code,
00164 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const = 0;
00165
00180 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00181 const std::vector<double> &ik_seed_state,
00182 double timeout,
00183 const std::vector<double> &consistency_limits,
00184 std::vector<double> &solution,
00185 const IKCallbackFn &solution_callback,
00186 moveit_msgs::MoveItErrorCodes &error_code,
00187 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const = 0;
00188
00213 virtual bool searchPositionIK(const std::vector<geometry_msgs::Pose> &ik_poses,
00214 const std::vector<double> &ik_seed_state,
00215 double timeout,
00216 const std::vector<double> &consistency_limits,
00217 std::vector<double> &solution,
00218 const IKCallbackFn &solution_callback,
00219 moveit_msgs::MoveItErrorCodes &error_code,
00220 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions(),
00221 const moveit::core::RobotState* context_state = NULL) const
00222 {
00223
00224 if (ik_poses.size() == 1)
00225 {
00226
00227 if (solution_callback)
00228 {
00229 return searchPositionIK(ik_poses[0],
00230 ik_seed_state,
00231 timeout,
00232 consistency_limits,
00233 solution,
00234 solution_callback,
00235 error_code,
00236 options);
00237 }
00238 else
00239 {
00240 return searchPositionIK(ik_poses[0],
00241 ik_seed_state,
00242 timeout,
00243 consistency_limits,
00244 solution,
00245 error_code,
00246 options);
00247 }
00248 }
00249
00250
00251 logError("moveit.kinematics_base: This kinematic solver does not support searchPositionIK with multiple poses");
00252 return false;
00253 }
00254
00262 virtual bool getPositionFK(const std::vector<std::string> &link_names,
00263 const std::vector<double> &joint_angles,
00264 std::vector<geometry_msgs::Pose> &poses) const = 0;
00265
00276 virtual void setValues(const std::string& robot_description,
00277 const std::string& group_name,
00278 const std::string& base_frame,
00279 const std::string& tip_frame,
00280 double search_discretization);
00281
00292 virtual void setValues(const std::string& robot_description,
00293 const std::string& group_name,
00294 const std::string& base_frame,
00295 const std::vector<std::string>& tip_frames,
00296 double search_discretization);
00297
00309 virtual bool initialize(const std::string& robot_description,
00310 const std::string& group_name,
00311 const std::string& base_frame,
00312 const std::string& tip_frame,
00313 double search_discretization) = 0;
00314
00326 virtual bool initialize(const std::string& robot_description,
00327 const std::string& group_name,
00328 const std::string& base_frame,
00329 const std::vector<std::string>& tip_frames,
00330 double search_discretization)
00331 {
00332
00333 if (tip_frames.size() == 1)
00334 {
00335 return initialize(robot_description,
00336 group_name,
00337 base_frame,
00338 tip_frames[0],
00339 search_discretization);
00340 }
00341
00342 logError("moveit.kinematics_base: This kinematic solver does not support initialization with more than one tip frames");
00343 return false;
00344 }
00345
00350 virtual const std::string& getGroupName() const
00351 {
00352 return group_name_;
00353 }
00354
00360 virtual const std::string& getBaseFrame() const
00361 {
00362 return base_frame_;
00363 }
00364
00371 virtual const std::string& getTipFrame() const
00372 {
00373 if (tip_frames_.size() > 1)
00374 logError("moveit.kinematics_base: This kinematic solver has more than one tip frame, do not call getTipFrame()");
00375
00376 return tip_frame_;
00377 }
00378
00384 virtual const std::vector<std::string>& getTipFrames() const
00385 {
00386 return tip_frames_;
00387 }
00388
00397 virtual bool setRedundantJoints(const std::vector<unsigned int> &redundant_joint_indices);
00398
00406 bool setRedundantJoints(const std::vector<std::string> &redundant_joint_names);
00407
00411 virtual void getRedundantJoints(std::vector<unsigned int> &redundant_joint_indices) const
00412 {
00413 redundant_joint_indices = redundant_joint_indices_;
00414 }
00415
00419 virtual const std::vector<std::string>& getJointNames() const = 0;
00420
00424 virtual const std::vector<std::string>& getLinkNames() const = 0;
00425
00426
00443 virtual const bool supportsGroup(const moveit::core::JointModelGroup *jmg,
00444 std::string* error_text_out = NULL) const;
00445
00449 void setSearchDiscretization(double sd)
00450 {
00451 search_discretization_ = sd;
00452 }
00453
00457 double getSearchDiscretization() const
00458 {
00459 return search_discretization_;
00460 }
00461
00464 void setDefaultTimeout(double timeout)
00465 {
00466 default_timeout_ = timeout;
00467 }
00468
00471 double getDefaultTimeout() const
00472 {
00473 return default_timeout_;
00474 }
00475
00479 virtual ~KinematicsBase() {}
00480
00481 KinematicsBase() :
00482 tip_frame_("DEPRECATED"),
00483
00484 search_discretization_(DEFAULT_SEARCH_DISCRETIZATION),
00485 default_timeout_(DEFAULT_TIMEOUT)
00486 {}
00487
00488 protected:
00489
00490 std::string robot_description_;
00491 std::string group_name_;
00492 std::string base_frame_;
00493 std::vector<std::string> tip_frames_;
00494 std::string tip_frame_;
00495
00496 double search_discretization_;
00497 double default_timeout_;
00498 std::vector<unsigned int> redundant_joint_indices_;
00499
00500 private:
00501
00502 std::string removeSlash(const std::string &str) const;
00503 };
00504
00505 typedef boost::shared_ptr<KinematicsBase> KinematicsBasePtr;
00506 typedef boost::shared_ptr<const KinematicsBase> KinematicsBaseConstPtr;
00507
00508 };
00509
00510 #endif