kdl_arm_kinematics_plugin.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
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 the Willow Garage 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 * Author: Sachin Chitta
00036 *********************************************************************/
00037 
00038 #ifndef KDL_ARM_KINEMATICS_PLUGIN_H_
00039 #define KDL_ARM_KINEMATICS_PLUGIN_H_
00040 
00041 // ROS
00042 #include <ros/ros.h>
00043 #include <tf/tf.h>
00044 #include <tf/transform_datatypes.h>
00045 #include <tf_conversions/tf_kdl.h>
00046 
00047 // System
00048 #include <boost/shared_ptr.hpp>
00049 #include <algorithm>
00050 #include <numeric>
00051 #include <cstring>
00052 
00053 // ROS msgs
00054 #include <geometry_msgs/PoseStamped.h>
00055 #include <kinematics_msgs/GetPositionFK.h>
00056 #include <kinematics_msgs/GetPositionIK.h>
00057 #include <kinematics_msgs/GetKinematicSolverInfo.h>
00058 #include <arm_navigation_msgs/ArmNavigationErrorCodes.h>
00059 
00060 // Plugin
00061 #include <kinematics_base/kinematics_base.h>
00062 
00063 // KDL
00064 #include <kdl/jntarray.hpp>
00065 #include <kdl_parser/kdl_parser.hpp>
00066 #include <kdl/chainiksolverpos_nr_jl.hpp>
00067 #include <kdl/chainiksolvervel_pinv.hpp>
00068 #include <kdl/chainfksolverpos_recursive.hpp>
00069 
00070 // MISC
00071 #include <angles/angles.h>
00072 #include <urdf/model.h>
00073 
00074 namespace arm_kinematics_constraint_aware
00075 {
00076 class KDLArmKinematicsPlugin : public kinematics::KinematicsBase
00077   {
00078     public:
00079 
00083     KDLArmKinematicsPlugin();
00084 
00089     bool isActive();
00090 
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 searchPositionIK(const geometry_msgs::Pose &ik_pose,
00112                           const std::vector<double> &ik_seed_state,
00113                           const double &timeout,
00114                           std::vector<double> &solution,
00115                           int &error_code);      
00116     
00126     virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00127                                   const std::vector<double> &ik_seed_state,
00128                                   const double &timeout,
00129                                   const unsigned int& redundancy,
00130                                   const double &consistency_limit,
00131                                   std::vector<double> &solution,
00132                                   int &error_code);      
00133     
00142     bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00143                           const std::vector<double> &ik_seed_state,
00144                           const double &timeout,
00145                           std::vector<double> &solution,
00146                           const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &desired_pose_callback,
00147                           const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &solution_callback,
00148                           int &error_code);    
00149 
00160        virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00161                                      const std::vector<double> &ik_seed_state,
00162                                      const double &timeout,
00163                                      const unsigned int& redundancy,
00164                                      const double &consistency_limit,
00165                                      std::vector<double> &solution,
00166                                      const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &desired_pose_callback,
00167                                      const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &solution_callback,
00168                                      int &error_code);      
00169 
00176     bool getPositionFK(const std::vector<std::string> &link_names,
00177                        const std::vector<double> &joint_angles, 
00178                        std::vector<geometry_msgs::Pose> &poses);
00179     
00184     bool initialize(const std::string& group_name,
00185                     const std::string& base_name,
00186                     const std::string& tip_name,
00187                     const double& search_discretization = .01);
00191     const std::vector<std::string>& getJointNames() const;
00192     
00196     const std::vector<std::string>& getLinkNames() const;
00197     
00198     protected:
00199 
00200     bool loadModel(const std::string xml);
00201     bool readJoints(urdf::Model &robot_model);
00202     int getJointIndex(const std::string &name);
00203     int getKDLSegmentIndex(const std::string &name);
00204     double genRandomNumber(const double &min, const double &max);
00205     KDL::JntArray getRandomConfiguration();
00206     KDL::JntArray getRandomConfiguration(const KDL::JntArray& seed_state,
00207                                          const unsigned int& redundancy,
00208                                          const double& consistency_limit);
00209 
00210     bool checkConsistency(const KDL::JntArray& seed_state,
00211                           const unsigned int& redundancy,
00212                           const double& consistency_limit, 
00213                           const KDL::JntArray& solution) const;
00214 
00215     int max_search_iterations_;
00216 
00217     bool active_;
00218     kinematics_msgs::KinematicSolverInfo chain_info_;
00219 
00220     boost::shared_ptr<KDL::ChainIkSolverVel_pinv> ik_solver_vel_;
00221     boost::shared_ptr<KDL::ChainFkSolverPos_recursive> fk_solver_;
00222     boost::shared_ptr<KDL::ChainIkSolverPos_NR_JL> ik_solver_pos_;
00223 
00224     unsigned int dimension_;
00225     KDL::Chain kdl_chain_;
00226     KDL::JntArray joint_min_, joint_max_;
00227 
00228     /*
00229       boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> solutionCallback_;    
00230       boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> desiredPoseCallback_;
00231       
00232       void desiredPoseCallback(const KDL::JntArray& jnt_array, 
00233       const KDL::Frame& ik_pose,
00234       arm_navigation_msgs::ArmNavigationErrorCodes& error_code);
00235       
00236       void jointSolutionCallback(const KDL::JntArray& jnt_array, 
00237       const KDL::Frame& ik_pose,
00238       arm_navigation_msgs::ArmNavigationErrorCodes& error_code);
00239     */
00240   };
00241 }
00242 
00243 #endif


arm_kinematics_constraint_aware
Author(s): Sachin Chitta
autogenerated on Mon Dec 2 2013 12:38:08