hand_description.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 *  Copyright (c) 2009, Willow Garage, Inc.
00004 *  All rights reserved.
00005 *
00006 *  Redistribution and use in source and binary forms, with or without
00007 *  modification, are permitted provided that the following conditions
00008 *  are met:
00009 *
00010 *   * Redistributions of source code must retain the above copyright
00011 *     notice, this list of conditions and the following disclaimer.
00012 *   * Redistributions in binary form must reproduce the above
00013 *     copyright notice, this list of conditions and the following
00014 *     disclaimer in the documentation and/or other materials provided
00015 *     with the distribution.
00016 *   * Neither the name of the Willow Garage nor the names of its
00017 *     contributors may be used to endorse or promote products derived
00018 *     from this software without specific prior written permission.
00019 *
00020 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 *  POSSIBILITY OF SUCH DAMAGE.
00032 *********************************************************************/
00033 #ifndef _HAND_DESCRIPTION_H_
00034 #define _HAND_DESCRIPTION_H_
00035 
00036 #include <ros/ros.h>
00037 
00038 #include <cmath>
00039 
00040 #include <geometry_msgs/Vector3.h>
00041 
00042 #include "object_manipulator/tools/exceptions.h"
00043 
00044 #include "configuration_loader.h"
00045 
00046 namespace object_manipulator {
00047 
00048   // aleeper: I sub-classed these parameter loading classes so we have a common class to work from.
00049   //          Hopefully it keeps things cleaner.
00050 
00051   class HandDescription : public ConfigurationLoader
00052 {
00053  private:
00054 
00055  public:
00056  HandDescription() {}
00057 
00058   inline std::string gripperFrame(std::string arm_name)
00059   {
00060     return getStringParam("/hand_description/" + arm_name + "/hand_frame");
00061   }
00062 
00063   inline std::string robotFrame(std::string arm_name)
00064   {
00065     return getStringParam("/hand_description/" + arm_name + "/robot_frame");
00066   }
00067   
00068   inline std::string attachedName(std::string arm_name)
00069   {
00070     return getStringParam("/hand_description/" + arm_name + "/attached_objects_name");
00071   }
00072   
00073   inline std::string attachLinkName(std::string arm_name)
00074   {
00075     return getStringParam("/hand_description/" + arm_name + "/attach_link");
00076   }
00077   
00078   inline std::string gripperCollisionName(std::string arm_name)
00079   {
00080     return getStringParam("/hand_description/" + arm_name + "/hand_group_name");
00081   }
00082   
00083   inline std::string armGroup(std::string arm_name)
00084   {
00085     return getStringParam("/hand_description/" + arm_name + "/arm_group_name");    
00086   }
00087   
00088   inline std::string handDatabaseName(std::string arm_name)
00089   {
00090     return getStringParam("/hand_description/" + arm_name + "/hand_database_name");
00091   }
00092   
00093   inline std::vector<std::string> handJointNames(std::string arm_name)
00094   {
00095     return getVectorParam("/hand_description/" + arm_name + "/hand_joints");
00096   }
00097   
00098   inline std::vector<std::string> gripperTouchLinkNames(std::string arm_name)
00099   {
00100     return getVectorParam("/hand_description/" + arm_name + "/hand_touch_links");
00101   }
00102   
00103   inline std::vector<std::string> fingertipLinks(std::string arm_name)
00104   {
00105     return getVectorParam("/hand_description/" + arm_name + "/hand_fingertip_links");
00106   }
00107 
00108   inline geometry_msgs::Vector3 approachDirection(std::string arm_name)
00109   {
00110     std::string name = "/hand_description/" + arm_name + "/hand_approach_direction";
00111     std::vector<double> values = getVectorDoubleParam(name);
00112     if ( values.size() != 3 )  throw BadParamException(name);
00113     double length = sqrt( values[0]*values[0] + values[1]*values[1] + values[2]*values[2] );
00114     if ( fabs(length) < 1.0e-5 ) throw BadParamException(name);
00115     geometry_msgs::Vector3 app;
00116     app.x = values[0] / length;
00117     app.y = values[1] / length;
00118     app.z = values[2] / length;
00119     return app;
00120   }
00121 
00122   inline std::vector<std::string> armJointNames(std::string arm_name)
00123   {
00124     return getVectorParam("/hand_description/" + arm_name + "/arm_joints");
00125   }
00126 
00127 };
00128 
00130 inline HandDescription& handDescription()
00131 {
00132   static HandDescription hand_description;
00133   return hand_description;
00134 }
00135 
00136 } //namespace object_manipulator
00137 
00138 #endif


object_manipulator
Author(s): Matei Ciocarlie and Kaijen Hsiao
autogenerated on Mon Oct 6 2014 02:59:50