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_ROS_PLANNING_KDL_KINEMATICS_PLUGIN_
00038 #define MOVEIT_ROS_PLANNING_KDL_KINEMATICS_PLUGIN_
00039
00040
00041 #include <ros/ros.h>
00042 #include <random_numbers/random_numbers.h>
00043
00044
00045 #include <boost/shared_ptr.hpp>
00046
00047
00048 #include <geometry_msgs/PoseStamped.h>
00049 #include <moveit_msgs/GetPositionFK.h>
00050 #include <moveit_msgs/GetPositionIK.h>
00051 #include <moveit_msgs/GetKinematicSolverInfo.h>
00052 #include <moveit_msgs/MoveItErrorCodes.h>
00053
00054
00055 #include <kdl/jntarray.hpp>
00056 #include <kdl/chainiksolvervel_pinv.hpp>
00057 #include <kdl/chainiksolverpos_nr_jl.hpp>
00058 #include <kdl/chainfksolverpos_recursive.hpp>
00059 #include <moveit/kdl_kinematics_plugin/chainiksolver_pos_nr_jl_mimic.hpp>
00060 #include <moveit/kdl_kinematics_plugin/chainiksolver_vel_pinv_mimic.hpp>
00061 #include <moveit/kdl_kinematics_plugin/joint_mimic.hpp>
00062
00063
00064 #include <moveit/kinematics_base/kinematics_base.h>
00065 #include <moveit/robot_model/robot_model.h>
00066 #include <moveit/robot_state/robot_state.h>
00067
00068 namespace kdl_kinematics_plugin
00069 {
00073 class KDLKinematicsPlugin : public kinematics::KinematicsBase
00074 {
00075 public:
00079 KDLKinematicsPlugin();
00080
00081 virtual bool
00082 getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
00083 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
00084 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00085
00086 virtual bool
00087 searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00088 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
00089 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00090
00091 virtual bool
00092 searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00093 const std::vector<double>& consistency_limits, std::vector<double>& solution,
00094 moveit_msgs::MoveItErrorCodes& error_code,
00095 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00096
00097 virtual bool searchPositionIK(
00098 const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00099 std::vector<double>& solution, const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
00100 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00101
00102 virtual bool
00103 searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00104 const std::vector<double>& consistency_limits, std::vector<double>& solution,
00105 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
00106 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00107
00108 virtual bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
00109 std::vector<geometry_msgs::Pose>& poses) const;
00110
00111 virtual bool initialize(const std::string& robot_description, const std::string& group_name,
00112 const std::string& base_name, const std::string& tip_name, double search_discretization);
00113
00117 const std::vector<std::string>& getJointNames() const;
00118
00122 const std::vector<std::string>& getLinkNames() const;
00123
00124 protected:
00141 bool searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00142 std::vector<double>& solution, const IKCallbackFn& solution_callback,
00143 moveit_msgs::MoveItErrorCodes& error_code, const std::vector<double>& consistency_limits,
00144 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00145
00146 virtual bool setRedundantJoints(const std::vector<unsigned int>& redundant_joint_indices);
00147
00148 private:
00149 bool timedOut(const ros::WallTime& start_time, double duration) const;
00150
00159 bool checkConsistency(const KDL::JntArray& seed_state, const std::vector<double>& consistency_limit,
00160 const KDL::JntArray& solution) const;
00161
00162 int getJointIndex(const std::string& name) const;
00163
00164 int getKDLSegmentIndex(const std::string& name) const;
00165
00166 void getRandomConfiguration(KDL::JntArray& jnt_array, bool lock_redundancy) const;
00167
00175 void getRandomConfiguration(const KDL::JntArray& seed_state, const std::vector<double>& consistency_limits,
00176 KDL::JntArray& jnt_array, bool lock_redundancy) const;
00177
00178 bool isRedundantJoint(unsigned int index) const;
00179
00180 bool active_;
00182 moveit_msgs::KinematicSolverInfo ik_chain_info_;
00184 moveit_msgs::KinematicSolverInfo fk_chain_info_;
00186 KDL::Chain kdl_chain_;
00187
00188 unsigned int dimension_;
00190 KDL::JntArray joint_min_, joint_max_;
00192 mutable random_numbers::RandomNumberGenerator random_number_generator_;
00193
00194 robot_model::RobotModelPtr robot_model_;
00195
00196 robot_state::RobotStatePtr state_, state_2_;
00197
00198 int num_possible_redundant_joints_;
00199 std::vector<unsigned int> redundant_joints_map_index_;
00200
00201
00202 bool position_ik_;
00203 robot_model::JointModelGroup* joint_model_group_;
00204 double max_solver_iterations_;
00205 double epsilon_;
00206 std::vector<JointMimic> mimic_joints_;
00207 };
00208 }
00209
00210 #endif