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 <moveit/macros/class_forward.h>
00043 #include <boost/function.hpp>
00044 #include <console_bridge/console.h>
00045 #include <string>
00046
00047 namespace moveit
00048 {
00049 namespace core
00050 {
00051 class JointModelGroup;
00052 class RobotState;
00053 }
00054 }
00055
00057 namespace kinematics
00058 {
00059
00060
00061
00062
00063
00064 namespace DiscretizationMethods
00065 {
00066 enum DiscretizationMethod
00067 {
00068 NO_DISCRETIZATION = 1,
00069 ALL_DISCRETIZED,
00070 SOME_DISCRETIZED,
00073 ALL_RANDOM_SAMPLED,
00074 SOME_RANDOM_SAMPLED
00076 };
00077 }
00078 typedef DiscretizationMethods::DiscretizationMethod DiscretizationMethod;
00079
00080
00081
00082
00083
00084 namespace KinematicErrors
00085 {
00086 enum KinematicError
00087 {
00088 OK = 1,
00089 UNSUPORTED_DISCRETIZATION_REQUESTED,
00090 DISCRETIZATION_NOT_INITIALIZED,
00092 MULTIPLE_TIPS_NOT_SUPPORTED,
00093 EMPTY_TIP_POSES,
00094 IK_SEED_OUTSIDE_LIMITS,
00095 SOLVER_NOT_ACTIVE,
00096 NO_SOLUTION
00098 };
00099 }
00100 typedef KinematicErrors::KinematicError KinematicError;
00101
00106 struct KinematicsQueryOptions
00107 {
00108 KinematicsQueryOptions()
00109 : lock_redundant_joints(false)
00110 , return_approximate_solution(false)
00111 , discretization_method(DiscretizationMethods::NO_DISCRETIZATION)
00112 {
00113 }
00114
00115 bool lock_redundant_joints;
00116 bool return_approximate_solution;
00117 DiscretizationMethod discretization_method;
00119 };
00120
00121
00122
00123
00124
00125
00126
00127
00128
00129
00130 struct KinematicsResult
00131 {
00132 KinematicError kinematic_error;
00133 double solution_percentage;
00135 };
00136
00137 MOVEIT_CLASS_FORWARD(KinematicsBase);
00138
00143 class KinematicsBase
00144 {
00145 public:
00146 static const double DEFAULT_SEARCH_DISCRETIZATION;
00147 static const double DEFAULT_TIMEOUT;
00148
00150 typedef boost::function<void(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_solution,
00151 moveit_msgs::MoveItErrorCodes& error_code)>
00152 IKCallbackFn;
00153
00164 virtual bool
00165 getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
00166 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
00167 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const = 0;
00168
00184 virtual bool getPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
00185 std::vector<std::vector<double> >& solutions, KinematicsResult& result,
00186 const kinematics::KinematicsQueryOptions& options) const;
00187
00201 virtual bool
00202 searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00203 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
00204 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const = 0;
00205
00221 virtual bool
00222 searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00223 const std::vector<double>& consistency_limits, std::vector<double>& solution,
00224 moveit_msgs::MoveItErrorCodes& error_code,
00225 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const = 0;
00226
00241 virtual bool searchPositionIK(
00242 const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00243 std::vector<double>& solution, const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
00244 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const = 0;
00245
00262 virtual bool
00263 searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00264 const std::vector<double>& consistency_limits, std::vector<double>& solution,
00265 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
00266 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const = 0;
00267
00293 virtual bool
00294 searchPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
00295 double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
00296 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
00297 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions(),
00298 const moveit::core::RobotState* context_state = NULL) const
00299 {
00300
00301 if (ik_poses.size() == 1)
00302 {
00303
00304 if (solution_callback)
00305 {
00306 return searchPositionIK(ik_poses[0], ik_seed_state, timeout, consistency_limits, solution, solution_callback,
00307 error_code, options);
00308 }
00309 else
00310 {
00311 return searchPositionIK(ik_poses[0], ik_seed_state, timeout, consistency_limits, solution, error_code, options);
00312 }
00313 }
00314
00315
00316 logError("moveit.kinematics_base: This kinematic solver does not support searchPositionIK with multiple poses");
00317 return false;
00318 }
00319
00327 virtual bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
00328 std::vector<geometry_msgs::Pose>& poses) const = 0;
00329
00340 virtual void setValues(const std::string& robot_description, const std::string& group_name,
00341 const std::string& base_frame, const std::string& tip_frame, double search_discretization);
00342
00353 virtual void setValues(const std::string& robot_description, const std::string& group_name,
00354 const std::string& base_frame, const std::vector<std::string>& tip_frames,
00355 double search_discretization);
00356
00368 virtual bool initialize(const std::string& robot_description, const std::string& group_name,
00369 const std::string& base_frame, const std::string& tip_frame,
00370 double search_discretization) = 0;
00371
00383 virtual bool initialize(const std::string& robot_description, const std::string& group_name,
00384 const std::string& base_frame, const std::vector<std::string>& tip_frames,
00385 double search_discretization)
00386 {
00387
00388 if (tip_frames.size() == 1)
00389 {
00390 return initialize(robot_description, group_name, base_frame, tip_frames[0], search_discretization);
00391 }
00392
00393 logError("moveit.kinematics_base: This kinematic solver does not support initialization with more than one tip "
00394 "frames");
00395 return false;
00396 }
00397
00402 virtual const std::string& getGroupName() const
00403 {
00404 return group_name_;
00405 }
00406
00412 virtual const std::string& getBaseFrame() const
00413 {
00414 return base_frame_;
00415 }
00416
00424 virtual const std::string& getTipFrame() const
00425 {
00426 if (tip_frames_.size() > 1)
00427 logError("moveit.kinematics_base: This kinematic solver has more than one tip frame, do not call getTipFrame()");
00428
00429 return tip_frame_;
00430 }
00431
00437 virtual const std::vector<std::string>& getTipFrames() const
00438 {
00439 return tip_frames_;
00440 }
00441
00451 virtual bool setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices);
00452
00460 bool setRedundantJoints(const std::vector<std::string>& redundant_joint_names);
00461
00465 virtual void getRedundantJoints(std::vector<unsigned int>& redundant_joint_indices) const
00466 {
00467 redundant_joint_indices = redundant_joint_indices_;
00468 }
00469
00473 virtual const std::vector<std::string>& getJointNames() const = 0;
00474
00478 virtual const std::vector<std::string>& getLinkNames() const = 0;
00479
00496 virtual bool supportsGroup(const moveit::core::JointModelGroup* jmg, std::string* error_text_out = NULL) const;
00497
00501 void setSearchDiscretization(double sd)
00502 {
00503 redundant_joint_discretization_.clear();
00504 for (std::vector<unsigned int>::iterator i = redundant_joint_indices_.begin(); i != redundant_joint_indices_.end();
00505 i++)
00506 {
00507 redundant_joint_discretization_[*i] = sd;
00508 }
00509 }
00510
00518 void setSearchDiscretization(const std::map<int, double>& discretization)
00519 {
00520 redundant_joint_discretization_.clear();
00521 redundant_joint_indices_.clear();
00522 for (std::map<int, double>::const_iterator i = discretization.begin(); i != discretization.end(); i++)
00523 {
00524 redundant_joint_discretization_.insert(*i);
00525 redundant_joint_indices_.push_back(i->first);
00526 }
00527 }
00528
00532 double getSearchDiscretization(int joint_index = 0) const
00533 {
00534 if (redundant_joint_discretization_.count(joint_index) > 0)
00535 {
00536 return redundant_joint_discretization_.at(joint_index);
00537 }
00538 else
00539 {
00540 return 0.0;
00541 }
00542 }
00543
00548 std::vector<DiscretizationMethod> getSupportedDiscretizationMethods() const
00549 {
00550 return supported_methods_;
00551 }
00552
00555 void setDefaultTimeout(double timeout)
00556 {
00557 default_timeout_ = timeout;
00558 }
00559
00562 double getDefaultTimeout() const
00563 {
00564 return default_timeout_;
00565 }
00566
00570 virtual ~KinematicsBase()
00571 {
00572 }
00573
00574 KinematicsBase()
00575 : tip_frame_("DEPRECATED")
00576 ,
00577
00578 search_discretization_(DEFAULT_SEARCH_DISCRETIZATION)
00579 , default_timeout_(DEFAULT_TIMEOUT)
00580 {
00581 supported_methods_.push_back(DiscretizationMethods::NO_DISCRETIZATION);
00582 }
00583
00584 protected:
00585 std::string robot_description_;
00586 std::string group_name_;
00587 std::string base_frame_;
00588 std::vector<std::string> tip_frames_;
00589 std::string tip_frame_;
00590
00591
00592 double search_discretization_;
00593
00594
00595
00596 double default_timeout_;
00597 std::vector<unsigned int> redundant_joint_indices_;
00598 std::map<int, double> redundant_joint_discretization_;
00599 std::vector<DiscretizationMethod> supported_methods_;
00600
00601 private:
00602 std::string removeSlash(const std::string& str) const;
00603 };
00604 };
00605
00606 #endif