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
00039 #ifndef REEM_KINEMATICS_PLUGIN_H_
00040 #define REEM_KINEMATICS_PLUGIN_H_
00041
00042
00043 #include <ros/ros.h>
00044 #include <tf/tf.h>
00045 #include <tf/transform_datatypes.h>
00046 #include <tf_conversions/tf_kdl.h>
00047
00048
00049 #include <boost/shared_ptr.hpp>
00050 #include <algorithm>
00051 #include <numeric>
00052 #include <cstring>
00053
00054
00055 #include <geometry_msgs/PoseStamped.h>
00056 #include <kinematics_msgs/GetPositionFK.h>
00057 #include <kinematics_msgs/GetPositionIK.h>
00058 #include <kinematics_msgs/GetKinematicSolverInfo.h>
00059 #include <arm_navigation_msgs/ArmNavigationErrorCodes.h>
00060
00061
00062 #include <kinematics_base/kinematics_base.h>
00063
00064
00065 #include <kdl/jntarray.hpp>
00066 #include <kdl_parser/kdl_parser.hpp>
00067 #include <kdl/chainfksolverpos_recursive.hpp>
00068
00069
00070 #include <reem_kinematics_constraint_aware/ik_solver.h>
00071
00072
00073 #include <angles/angles.h>
00074
00075 namespace reem_kinematics_constraint_aware
00076 {
00077 class ReemKinematicsPlugin : public kinematics::KinematicsBase
00078 {
00079 public:
00080
00084 ReemKinematicsPlugin();
00085
00090 bool isActive();
00091
00098 bool getPositionIK(const geometry_msgs::Pose &ik_pose,
00099 const std::vector<double> &ik_seed_state,
00100 std::vector<double> &solution,
00101 int &error_code);
00102
00111 bool getPositionIK(const geometry_msgs::Pose &ik_pose,
00112 const std::vector<double> &ik_seed_state,
00113 const std::vector<double> &posture,
00114 std::vector<double> &solution,
00115 int &error_code);
00116
00125 bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00126 const std::vector<double> &ik_seed_state,
00127 const double &timeout,
00128 std::vector<double> &solution,
00129 int &error_code);
00130
00140 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00141 const std::vector<double> &ik_seed_state,
00142 const double &timeout,
00143 const unsigned int& redundancy,
00144 const double &consistency_limit,
00145 std::vector<double> &solution,
00146 int &error_code);
00147
00156 bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00157 const std::vector<double> &ik_seed_state,
00158 const double &timeout,
00159 std::vector<double> &solution,
00160 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &desired_pose_callback,
00161 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &solution_callback,
00162 int &error_code);
00163
00174 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00175 const std::vector<double> &ik_seed_state,
00176 const double &timeout,
00177 const unsigned int& redundancy,
00178 const double &consistency_limit,
00179 std::vector<double> &solution,
00180 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &desired_pose_callback,
00181 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &solution_callback,
00182 int &error_code);
00183
00190 bool getPositionFK(const std::vector<std::string> &link_names,
00191 const std::vector<double> &joint_angles,
00192 std::vector<geometry_msgs::Pose> &poses);
00193
00198 virtual bool initialize(const std::string& group_name,
00199 const std::string& base_name,
00200 const std::string& tip_name,
00201 const double& search_discretization = .01);
00202
00207 std::string getBaseFrame();
00208
00212 std::string getToolFrame();
00213
00217 const std::vector<std::string>& getJointNames() const;
00218
00222 const std::vector<std::string>& getLinkNames() const;
00223
00224 protected:
00225
00226 bool loadModel(const std::string xml);
00227 bool readJoints(urdf::Model &robot_model);
00228 int getJointIndex(const std::string &name);
00229 int getKDLSegmentIndex(const std::string &name);
00230 double genRandomNumber(const double &min, const double &max);
00231 KDL::JntArray getRandomConfiguration();
00232 KDL::JntArray getRandomConfiguration(const KDL::JntArray& seed_state,
00233 const unsigned int& redundancy,
00234 const double& consistency_limit);
00235
00236 bool checkConsistency(const KDL::JntArray& seed_state,
00237 const unsigned int& redundancy,
00238 const double& consistency_limit,
00239 const KDL::JntArray& solution) const;
00240
00241 int max_search_iterations_;
00242
00243 bool active_;
00244 kinematics_msgs::KinematicSolverInfo chain_info_;
00245
00246 boost::shared_ptr<KDL::ChainFkSolverPos_recursive> fk_solver_;
00247 boost::shared_ptr<IkSolver> ik_solver_;
00248
00249 unsigned int dimension_;
00250 KDL::Chain kdl_chain_;
00251 KDL::JntArray joint_min_, joint_max_;
00252 std::vector<double> default_posture_;
00253 };
00254 }
00255
00256 #endif