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 namespace object_manipulator {
00045 
00046 class HandDescription
00047 {
00048  private:
00050   ros::NodeHandle root_nh_;
00051 
00052   inline std::string getStringParam(std::string name)
00053   {
00054     std::string value;
00055     if (!root_nh_.getParamCached(name, value)) throw MissingParamException(name);
00056     //ROS_INFO_STREAM("Hand description param " << name << " resolved to " << value);
00057     return value;
00058   }
00059 
00060   inline std::vector<std::string> getVectorParam(std::string name)
00061   {
00062     XmlRpc::XmlRpcValue list;
00063     if (!root_nh_.getParamCached(name, list)) throw MissingParamException(name);
00064     if (list.getType() != XmlRpc::XmlRpcValue::TypeArray) throw BadParamException(name);
00065     //ROS_INFO_STREAM("Hand description vector param " << name << " resolved to:");
00066     std::vector<std::string> values;
00067     for (int32_t i=0; i<list.size(); i++)
00068     {
00069       if (list[i].getType() != XmlRpc::XmlRpcValue::TypeString) throw BadParamException(name);
00070       values.push_back( static_cast<std::string>(list[i]) );
00071       //ROS_INFO_STREAM("  " << values.back());
00072     }
00073     return values;
00074   }
00075 
00076   inline std::vector<double> getVectorDoubleParam(std::string name)
00077   {
00078     XmlRpc::XmlRpcValue list;
00079     if (!root_nh_.getParamCached(name, list)) throw MissingParamException(name);
00080     if (list.getType() != XmlRpc::XmlRpcValue::TypeArray) throw BadParamException(name);
00081     std::vector<double> values;
00082     for (int32_t i=0; i<list.size(); i++)
00083     {
00084       if (list[i].getType() != XmlRpc::XmlRpcValue::TypeDouble) throw BadParamException(name);
00085       values.push_back( static_cast<double>(list[i]) );
00086     }
00087     return values;
00088   }
00089 
00090  public:
00091  HandDescription() : root_nh_("~") {}
00092 
00093   inline std::string gripperFrame(std::string arm_name)
00094   {
00095     return getStringParam("/hand_description/" + arm_name + "/hand_frame");
00096   }
00097 
00098   inline std::string robotFrame(std::string arm_name)
00099   {
00100     return getStringParam("/hand_description/" + arm_name + "/robot_frame");
00101   }
00102 
00103   inline std::string attachedName(std::string arm_name)
00104   {
00105     return getStringParam("/hand_description/" + arm_name + "/attached_objects_name");
00106   }
00107 
00108   inline std::string attachLinkName(std::string arm_name)
00109   {
00110     return getStringParam("/hand_description/" + arm_name + "/attach_link");
00111   }
00112 
00113   inline std::string gripperCollisionName(std::string arm_name)
00114   {
00115     return getStringParam("/hand_description/" + arm_name + "/hand_group_name");
00116   }
00117 
00118   inline std::string armGroup(std::string arm_name)
00119   {
00120     return getStringParam("/hand_description/" + arm_name + "/arm_group_name");
00121   }
00122 
00123   inline std::string handDatabaseName(std::string arm_name)
00124   {
00125     return getStringParam("/hand_description/" + arm_name + "/hand_database_name");
00126   }
00127 
00128   inline std::vector<std::string> handJointNames(std::string arm_name)
00129   {
00130     return getVectorParam("/hand_description/" + arm_name + "/hand_joints");
00131   }
00132 
00133   inline std::vector<std::string> gripperTouchLinkNames(std::string arm_name)
00134   {
00135     return getVectorParam("/hand_description/" + arm_name + "/hand_touch_links");
00136   }
00137 
00138   inline std::vector<std::string> fingertipLinks(std::string arm_name)
00139   {
00140     return getVectorParam("/hand_description/" + arm_name + "/hand_fingertip_links");
00141   }
00142 
00143   inline geometry_msgs::Vector3 approachDirection(std::string arm_name)
00144   {
00145     std::string name = "/hand_description/" + arm_name + "/hand_approach_direction";
00146     std::vector<double> values = getVectorDoubleParam(name);
00147     if ( values.size() != 3 )  throw BadParamException(name);
00148     double length = sqrt( values[0]*values[0] + values[1]*values[1] + values[2]*values[2] );
00149     if ( fabs(length) < 1.0e-5 ) throw BadParamException(name);
00150     geometry_msgs::Vector3 app;
00151     app.x = values[0] / length;
00152     app.y = values[1] / length;
00153     app.z = values[2] / length;
00154     return app;
00155   }
00156 
00157 };
00158 
00160 inline HandDescription& handDescription()
00161 {
00162   static HandDescription hand_description;
00163   return hand_description;
00164 }
00165 
00166 } //namespace object_manipulator
00167 
00168 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


katana_object_manipulator
Author(s): Henning Deeken
autogenerated on Thu Jan 3 2013 14:44:42