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 #ifndef MOVEIT_ROS_PLANNING_KDL_KINEMATICS_PLUGIN_
00039 #define MOVEIT_ROS_PLANNING_KDL_KINEMATICS_PLUGIN_
00040
00041
00042 #include <ros/ros.h>
00043 #include <random_numbers/random_numbers.h>
00044
00045
00046 #include <boost/shared_ptr.hpp>
00047
00048
00049 #include <geometry_msgs/PoseStamped.h>
00050 #include <moveit_msgs/GetPositionFK.h>
00051 #include <moveit_msgs/GetPositionIK.h>
00052 #include <moveit_msgs/GetKinematicSolverInfo.h>
00053 #include <moveit_msgs/MoveItErrorCodes.h>
00054
00055
00056 #include <kdl/jntarray.hpp>
00057 #include <kdl/chainiksolvervel_pinv.hpp>
00058 #include <kdl/chainiksolverpos_nr_jl.hpp>
00059 #include <kdl/chainfksolverpos_recursive.hpp>
00060 #include <moveit/kdl_kinematics_plugin/chainiksolver_pos_nr_jl_mimic.hpp>
00061 #include <moveit/kdl_kinematics_plugin/chainiksolver_vel_pinv_mimic.hpp>
00062 #include <moveit/kdl_kinematics_plugin/chainiksolver_pos_nr_jl_mimic.hpp>
00063 #include <moveit/kdl_kinematics_plugin/joint_mimic.hpp>
00064
00065
00066 #include <moveit/kinematics_base/kinematics_base.h>
00067 #include <moveit/robot_model/robot_model.h>
00068 #include <moveit/robot_state/robot_state.h>
00069
00070 namespace kdl_kinematics_plugin
00071 {
00075 class KDLKinematicsPlugin : public kinematics::KinematicsBase
00076 {
00077 public:
00078
00082 KDLKinematicsPlugin();
00083
00084 virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose,
00085 const std::vector<double> &ik_seed_state,
00086 std::vector<double> &solution,
00087 moveit_msgs::MoveItErrorCodes &error_code,
00088 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00089
00090 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00091 const std::vector<double> &ik_seed_state,
00092 double timeout,
00093 std::vector<double> &solution,
00094 moveit_msgs::MoveItErrorCodes &error_code,
00095 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00096
00097 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00098 const std::vector<double> &ik_seed_state,
00099 double timeout,
00100 const std::vector<double> &consistency_limits,
00101 std::vector<double> &solution,
00102 moveit_msgs::MoveItErrorCodes &error_code,
00103 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00104
00105 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00106 const std::vector<double> &ik_seed_state,
00107 double timeout,
00108 std::vector<double> &solution,
00109 const IKCallbackFn &solution_callback,
00110 moveit_msgs::MoveItErrorCodes &error_code,
00111 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00112
00113 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00114 const std::vector<double> &ik_seed_state,
00115 double timeout,
00116 const std::vector<double> &consistency_limits,
00117 std::vector<double> &solution,
00118 const IKCallbackFn &solution_callback,
00119 moveit_msgs::MoveItErrorCodes &error_code,
00120 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00121
00122 virtual bool getPositionFK(const std::vector<std::string> &link_names,
00123 const std::vector<double> &joint_angles,
00124 std::vector<geometry_msgs::Pose> &poses) const;
00125
00126 virtual bool initialize(const std::string &robot_description,
00127 const std::string &group_name,
00128 const std::string &base_name,
00129 const std::string &tip_name,
00130 double search_discretization);
00131
00135 const std::vector<std::string>& getJointNames() const;
00136
00140 const std::vector<std::string>& getLinkNames() const;
00141
00142 protected:
00143
00159 bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00160 const std::vector<double> &ik_seed_state,
00161 double timeout,
00162 std::vector<double> &solution,
00163 const IKCallbackFn &solution_callback,
00164 moveit_msgs::MoveItErrorCodes &error_code,
00165 const std::vector<double> &consistency_limits,
00166 const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00167
00168 virtual bool setRedundantJoints(const std::vector<unsigned int> &redundant_joint_indices);
00169
00170 private:
00171
00172 bool timedOut(const ros::WallTime &start_time, double duration) const;
00173
00174
00182 bool checkConsistency(const KDL::JntArray& seed_state,
00183 const std::vector<double> &consistency_limit,
00184 const KDL::JntArray& solution) const;
00185
00186 int getJointIndex(const std::string &name) const;
00187
00188 int getKDLSegmentIndex(const std::string &name) const;
00189
00190 void getRandomConfiguration(KDL::JntArray &jnt_array, bool lock_redundancy) const;
00191
00198 void getRandomConfiguration(const KDL::JntArray& seed_state,
00199 const std::vector<double> &consistency_limits,
00200 KDL::JntArray &jnt_array,
00201 bool lock_redundancy) const;
00202
00203 bool isRedundantJoint(unsigned int index) const;
00204
00205 bool active_;
00207 moveit_msgs::KinematicSolverInfo ik_chain_info_;
00209 moveit_msgs::KinematicSolverInfo fk_chain_info_;
00211 KDL::Chain kdl_chain_;
00212
00213 unsigned int dimension_;
00215 KDL::JntArray joint_min_, joint_max_;
00217 mutable random_numbers::RandomNumberGenerator random_number_generator_;
00218
00219 robot_model::RobotModelPtr kinematic_model_;
00220
00221 robot_state::RobotStatePtr kinematic_state_, kinematic_state_2_;
00222
00223 int num_possible_redundant_joints_;
00224 std::vector<unsigned int> redundant_joints_map_index_;
00225
00226
00227 bool position_ik_;
00228 robot_model::JointModelGroup* joint_model_group_;
00229 double max_solver_iterations_;
00230 double epsilon_;
00231 std::vector<kdl_kinematics_plugin::JointMimic> mimic_joints_;
00232
00233 };
00234 }
00235
00236 #endif