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
00038
00039
00040
00041
00042 #ifndef MOVEIT_ROS_PLANNING_SRV_KINEMATICS_PLUGIN_
00043 #define MOVEIT_ROS_PLANNING_SRV_KINEMATICS_PLUGIN_
00044
00045
00046 #include <ros/ros.h>
00047
00048
00049 #include <boost/shared_ptr.hpp>
00050
00051
00052 #include <geometry_msgs/PoseStamped.h>
00053 #include <moveit_msgs/GetPositionFK.h>
00054 #include <moveit_msgs/GetPositionIK.h>
00055 #include <moveit_msgs/GetKinematicSolverInfo.h>
00056 #include <moveit_msgs/MoveItErrorCodes.h>
00057
00058
00059 #include <moveit/kinematics_base/kinematics_base.h>
00060 #include <moveit/robot_model/robot_model.h>
00061 #include <moveit/robot_state/robot_state.h>
00062
00063 namespace srv_kinematics_plugin
00064 {
00069 class SrvKinematicsPlugin : public kinematics::KinematicsBase
00070 {
00071 public:
00075 SrvKinematicsPlugin();
00076
00077 virtual bool
00078 getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
00079 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
00080 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00081
00082 virtual bool
00083 searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00084 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
00085 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00086
00087 virtual bool
00088 searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00089 const std::vector<double>& consistency_limits, std::vector<double>& solution,
00090 moveit_msgs::MoveItErrorCodes& error_code,
00091 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00092
00093 virtual bool searchPositionIK(
00094 const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00095 std::vector<double>& solution, const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
00096 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00097
00098 virtual bool
00099 searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00100 const std::vector<double>& consistency_limits, std::vector<double>& solution,
00101 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
00102 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00103
00104 virtual bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
00105 std::vector<geometry_msgs::Pose>& poses) const;
00106
00107 virtual bool initialize(const std::string& robot_description, const std::string& group_name,
00108 const std::string& base_name, const std::string& tip_frame, double search_discretization)
00109 {
00110 std::vector<std::string> tip_frames;
00111 tip_frames.push_back(tip_frame);
00112 return initialize(robot_description, group_name, base_name, tip_frames, search_discretization);
00113 }
00114
00115 virtual bool initialize(const std::string& robot_description, const std::string& group_name,
00116 const std::string& base_name, const std::vector<std::string>& tip_frames,
00117 double search_discretization);
00118
00122 const std::vector<std::string>& getJointNames() const;
00123
00127 const std::vector<std::string>& getLinkNames() const;
00128
00132 const std::vector<std::string>& getVariableNames() const;
00133
00134 protected:
00135 virtual bool
00136 searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00137 std::vector<double>& solution, const IKCallbackFn& solution_callback,
00138 moveit_msgs::MoveItErrorCodes& error_code, const std::vector<double>& consistency_limits,
00139 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00140
00141 virtual bool
00142 searchPositionIK(const std::vector<geometry_msgs::Pose>& ik_poses, const std::vector<double>& ik_seed_state,
00143 double timeout, const std::vector<double>& consistency_limits, std::vector<double>& solution,
00144 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
00145 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00146
00147 virtual bool setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices);
00148
00149 private:
00150 bool timedOut(const ros::WallTime& start_time, double duration) const;
00151
00152 int getJointIndex(const std::string& name) const;
00153
00154 bool isRedundantJoint(unsigned int index) const;
00155
00156 bool active_;
00158 moveit_msgs::KinematicSolverInfo ik_group_info_;
00160 unsigned int dimension_;
00162 robot_model::RobotModelPtr robot_model_;
00163 robot_model::JointModelGroup* joint_model_group_;
00164
00165 robot_state::RobotStatePtr robot_state_;
00166
00167 int num_possible_redundant_joints_;
00168
00169 boost::shared_ptr<ros::ServiceClient> ik_service_client_;
00170 };
00171 }
00172
00173 #endif