$search
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 Willow Garage, Inc. 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 #ifndef KINEMATICS_BASE_ 00038 #define KINEMATICS_BASE_ 00039 00040 #include <geometry_msgs/PoseStamped.h> 00041 #include <arm_navigation_msgs/RobotState.h> 00042 00043 #include <kinematics_msgs/GetPositionIK.h> 00044 #include <kinematics_msgs/GetPositionFK.h> 00045 00046 namespace kinematics { 00047 00048 static const int SUCCESS = 1; 00049 static const int TIMED_OUT = -1; 00050 static const int NO_IK_SOLUTION = -2; 00051 static const int FRAME_TRANSFORM_FAILURE = -3; 00052 static const int IK_LINK_INVALID = -4; 00053 static const int IK_LINK_IN_COLLISION = -5; 00054 static const int STATE_IN_COLLISION = -6; 00055 static const int INVALID_LINK_NAME = -7; 00056 static const int GOAL_CONSTRAINTS_VIOLATED = -7; 00057 static const int INACTIVE = -8; 00058 00063 class KinematicsBase{ 00064 public: 00072 virtual bool getPositionIK(const geometry_msgs::Pose &ik_pose, 00073 const std::vector<double> &ik_seed_state, 00074 std::vector<double> &solution, 00075 int &error_code) = 0; 00076 00085 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose, 00086 const std::vector<double> &ik_seed_state, 00087 const double &timeout, 00088 std::vector<double> &solution, 00089 int &error_code) = 0; 00090 00099 virtual bool searchPositionIK(const geometry_msgs::Pose &ik_pose, 00100 const std::vector<double> &ik_seed_state, 00101 const double &timeout, 00102 std::vector<double> &solution, 00103 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &desired_pose_callback, 00104 const boost::function<void(const geometry_msgs::Pose &ik_pose,const std::vector<double> &ik_solution,int &error_code)> &solution_callback, 00105 int &error_code) = 0; 00106 00113 virtual bool getPositionFK(const std::vector<std::string> &link_names, 00114 const std::vector<double> &joint_angles, 00115 std::vector<geometry_msgs::Pose> &poses) = 0; 00116 00121 virtual bool initialize(std::string name) = 0; 00122 00127 virtual std::string getBaseFrame() = 0; 00128 00132 virtual std::string getToolFrame() = 0; 00133 00137 virtual std::vector<std::string> getJointNames() = 0; 00138 00142 virtual std::vector<std::string> getLinkNames() = 0; 00143 00147 virtual ~KinematicsBase(){} 00148 00149 protected: 00150 KinematicsBase(){} 00151 }; 00152 }; 00153 00154 #endif