reem_arm_kinematics_plugin.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (Modified BSD License)
00003  *
00004  *  Copyright (c) 2012, PAL Robotics, S.L.
00005  *  Copyright (c) 2008, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of PAL Robotics, S.L. nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  */
00035 
00039 #ifndef REEM_KINEMATICS_PLUGIN_H_
00040 #define REEM_KINEMATICS_PLUGIN_H_
00041 
00042 // ROS
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 // System
00049 #include <boost/shared_ptr.hpp>
00050 #include <algorithm>
00051 #include <numeric>
00052 #include <cstring>
00053 
00054 // ROS msgs
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 // Plugin
00062 #include <kinematics_base/kinematics_base.h>
00063 
00064 // KDL
00065 #include <kdl/jntarray.hpp>
00066 #include <kdl_parser/kdl_parser.hpp>
00067 #include <kdl/chainfksolverpos_recursive.hpp>
00068 
00069 // Local
00070 #include <reem_kinematics_constraint_aware/ik_solver.h>
00071 
00072 // MISC
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


reem_kinematics_constraint_aware
Author(s): Adolfo Rodriguez Tsouroukdissian, Hilario Tome.
autogenerated on Thu Jan 2 2014 11:42:41