trac_ik_kinematics_plugin.hpp
Go to the documentation of this file.
00001 /********************************************************************************
00002 Copyright (c) 2015, TRACLabs, Inc.
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without modification,
00006  are permitted provided that the following conditions are met:
00007 
00008     1. Redistributions of source code must retain the above copyright notice,
00009        this list of conditions and the following disclaimer.
00010 
00011     2. Redistributions in binary form must reproduce the above copyright notice,
00012        this list of conditions and the following disclaimer in the documentation
00013        and/or other materials provided with the distribution.
00014 
00015     3. Neither the name of the copyright holder nor the names of its contributors
00016        may be used to endorse or promote products derived from this software
00017        without specific prior written permission.
00018 
00019 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00020 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00021 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
00022 IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT,
00023 INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00024 BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
00025 DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00026 LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00027 OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
00028 OF THE POSSIBILITY OF SUCH DAMAGE.
00029 ********************************************************************************/
00030 
00031 #ifndef TRAC_IK_KINEMATICS_PLUGIN_
00032 #define TRAC_IK_KINEMATICS_PLUGIN_
00033 
00034 #include <moveit/kinematics_base/kinematics_base.h>
00035 #include <kdl/chain.hpp>
00036 
00037 namespace trac_ik_kinematics_plugin
00038 {
00039 
00040   class TRAC_IKKinematicsPlugin : public kinematics::KinematicsBase
00041   {
00042     std::vector<std::string> joint_names_;
00043     std::vector<std::string> link_names_;
00044 
00045     uint num_joints_;
00046     bool active_; // Internal variable that indicates whether solvers are configured and ready
00047 
00048     KDL::Chain chain;
00049     bool position_ik_;
00050 
00051     KDL::JntArray joint_min, joint_max;
00052 
00053     std::string solve_type;
00054 
00055   public:
00056     const std::vector<std::string>& getJointNames() const { return joint_names_; }
00057     const std::vector<std::string>& getLinkNames() const { return link_names_; }
00058 
00059 
00063     TRAC_IKKinematicsPlugin(): active_(false), position_ik_(false){}
00064 
00065     ~TRAC_IKKinematicsPlugin() {
00066     }
00067 
00077     // Returns the first IK solution that is within joint limits, this is called by get_ik() service
00078     bool getPositionIK(const geometry_msgs::Pose &ik_pose,
00079                        const std::vector<double> &ik_seed_state,
00080                        std::vector<double> &solution,
00081                        moveit_msgs::MoveItErrorCodes &error_code,
00082                        const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00083 
00092     bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00093                           const std::vector<double> &ik_seed_state,
00094                           double timeout,
00095                           std::vector<double> &solution,
00096                           moveit_msgs::MoveItErrorCodes &error_code,
00097                           const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00098 
00108     bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00109                           const std::vector<double> &ik_seed_state,
00110                           double timeout,
00111                           const std::vector<double> &consistency_limits,
00112                           std::vector<double> &solution,
00113                           moveit_msgs::MoveItErrorCodes &error_code,
00114                           const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00115 
00124     bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00125                           const std::vector<double> &ik_seed_state,
00126                           double timeout,
00127                           std::vector<double> &solution,
00128                           const IKCallbackFn &solution_callback,
00129                           moveit_msgs::MoveItErrorCodes &error_code,
00130                           const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00131 
00142     bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00143                           const std::vector<double> &ik_seed_state,
00144                           double timeout,
00145                           const std::vector<double> &consistency_limits,
00146                           std::vector<double> &solution,
00147                           const IKCallbackFn &solution_callback,
00148                           moveit_msgs::MoveItErrorCodes &error_code,
00149                           const kinematics::KinematicsQueryOptions &options = kinematics::KinematicsQueryOptions()) const;
00150 
00151     bool searchPositionIK(const geometry_msgs::Pose &ik_pose,
00152                           const std::vector<double> &ik_seed_state,
00153                           double timeout,
00154                           std::vector<double> &solution,
00155                           const IKCallbackFn &solution_callback,
00156                           moveit_msgs::MoveItErrorCodes &error_code,
00157                           const std::vector<double> &consistency_limits,
00158                           const kinematics::KinematicsQueryOptions &options) const;
00159 
00160 
00172     bool getPositionFK(const std::vector<std::string> &link_names,
00173                        const std::vector<double> &joint_angles,
00174                        std::vector<geometry_msgs::Pose> &poses) const;
00175 
00176 
00177     bool initialize(const std::string &robot_description,
00178                     const std::string& group_name,
00179                     const std::string& base_name,
00180                     const std::string& tip_name,
00181                     double search_discretization);
00182 
00183   private:
00184 
00185     int getKDLSegmentIndex(const std::string &name) const;
00186 
00187   }; // end class
00188 }
00189 
00190 #endif


trac_ik_kinematics_plugin
Author(s): Patrick Beeson
autogenerated on Thu Sep 21 2017 02:53:14