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_LMA_KINEMATICS_PLUGIN_H
00038 #define MOVEIT_ROS_PLANNING_LMA_KINEMATICS_PLUGIN_H
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/lma_kinematics_plugin/chainiksolver_pos_lma_jl_mimic.h>
00060 #include <moveit/lma_kinematics_plugin/chainiksolver_vel_pinv_mimic.h>
00061 #include <moveit/lma_kinematics_plugin/joint_mimic.h>
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 lma_kinematics_plugin
00069 {
00074 class LMAKinematicsPlugin : public kinematics::KinematicsBase
00075 {
00076 public:
00080 LMAKinematicsPlugin();
00081
00082 virtual bool
00083 getPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state,
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 std::vector<double>& solution, moveit_msgs::MoveItErrorCodes& error_code,
00090 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00091
00092 virtual bool
00093 searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00094 const std::vector<double>& consistency_limits, std::vector<double>& solution,
00095 moveit_msgs::MoveItErrorCodes& error_code,
00096 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00097
00098 virtual bool searchPositionIK(
00099 const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00100 std::vector<double>& solution, const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
00101 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00102
00103 virtual bool
00104 searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00105 const std::vector<double>& consistency_limits, std::vector<double>& solution,
00106 const IKCallbackFn& solution_callback, moveit_msgs::MoveItErrorCodes& error_code,
00107 const kinematics::KinematicsQueryOptions& options = kinematics::KinematicsQueryOptions()) const;
00108
00109 virtual bool getPositionFK(const std::vector<std::string>& link_names, const std::vector<double>& joint_angles,
00110 std::vector<geometry_msgs::Pose>& poses) const;
00111
00112 virtual bool initialize(const std::string& robot_description, const std::string& group_name,
00113 const std::string& base_name, const std::string& tip_name, double search_discretization);
00114
00118 const std::vector<std::string>& getJointNames() const;
00119
00123 const std::vector<std::string>& getLinkNames() const;
00124
00125 protected:
00142 bool searchPositionIK(const geometry_msgs::Pose& ik_pose, const std::vector<double>& ik_seed_state, double timeout,
00143 std::vector<double>& solution, const IKCallbackFn& solution_callback,
00144 moveit_msgs::MoveItErrorCodes& error_code, const std::vector<double>& consistency_limits,
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
00160 bool checkConsistency(const KDL::JntArray& seed_state, const std::vector<double>& consistency_limit,
00161 const KDL::JntArray& solution) const;
00162
00163 int getJointIndex(const std::string& name) const;
00164
00165 int getKDLSegmentIndex(const std::string& name) const;
00166
00167 void getRandomConfiguration(KDL::JntArray& jnt_array, bool lock_redundancy) const;
00168
00176 void getRandomConfiguration(const KDL::JntArray& seed_state, const std::vector<double>& consistency_limits,
00177 KDL::JntArray& jnt_array, bool lock_redundancy) const;
00178
00179 bool isRedundantJoint(unsigned int index) const;
00180
00181 bool active_;
00183 moveit_msgs::KinematicSolverInfo ik_chain_info_;
00185 moveit_msgs::KinematicSolverInfo fk_chain_info_;
00187 KDL::Chain kdl_chain_;
00188
00189 unsigned int dimension_;
00191 KDL::JntArray joint_min_, joint_max_;
00193 mutable random_numbers::RandomNumberGenerator random_number_generator_;
00194
00195 robot_model::RobotModelPtr robot_model_;
00196
00197 robot_state::RobotStatePtr state_, state_2_;
00198
00199 int num_possible_redundant_joints_;
00200 std::vector<unsigned int> redundant_joints_map_index_;
00201
00202
00203 bool position_ik_;
00204 robot_model::JointModelGroup* joint_model_group_;
00205 double max_solver_iterations_;
00206 double epsilon_;
00207 std::vector<JointMimic> mimic_joints_;
00208 };
00209 }
00210
00211 #endif