param_utils.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  * Copyright (c) 2012, Southwest Research Institute
00005  * All rights reserved.
00006  *
00007  * Redistribution and use in source and binary forms, with or without
00008  * modification, are permitted provided that the following conditions 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 copyright
00013  *       notice, this list of conditions and the following disclaimer in the
00014  *       documentation and/or other materials provided with the distribution.
00015  *       * Neither the name of the Southwest Research Institute, nor the names
00016  *       of its contributors may be used to endorse or promote products derived
00017  *       from this software without specific prior written permission.
00018  *
00019  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00020  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00021  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00022  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00023  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00024  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00025  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00026  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00027  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00028  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00029  * POSSIBILITY OF SUCH DAMAGE.
00030  */
00031 
00032 #include <sstream>
00033 
00034 #include "industrial_utils/param_utils.h"
00035 #include "ros/ros.h"
00036 #include "urdf/model.h"
00037 
00038 namespace industrial_utils
00039 {
00040 namespace param
00041 {
00042 bool getListParam(const std::string param_name, std::vector<std::string> & list_param)
00043 {
00044   bool rtn = false;
00045   XmlRpc::XmlRpcValue rpc_list;
00046 
00047   list_param.clear(); //clear out return value
00048 
00049   rtn = ros::param::get(param_name, rpc_list);
00050 
00051   if (rtn)
00052   {
00053     rtn = (rpc_list.getType() == XmlRpc::XmlRpcValue::TypeArray);
00054 
00055     if (rtn)
00056     {
00057 
00058       for (int i = 0; i < rpc_list.size(); ++i)
00059       {
00060         rtn = (rpc_list[i].getType() == XmlRpc::XmlRpcValue::TypeString);
00061         if (rtn)
00062         {
00063           ROS_INFO_STREAM("Adding " << rpc_list[i] << " to list parameter");
00064           list_param.push_back(static_cast<std::string>(rpc_list[i]));
00065         }
00066         else
00067         {
00068           ROS_ERROR_STREAM("List item for: " << param_name << " not of string type");
00069         }
00070       }
00071     }
00072     else
00073     {
00074       ROS_ERROR_STREAM("Parameter: " << param_name << " not of list type");
00075     }
00076   }
00077   else
00078   {
00079     ROS_ERROR_STREAM("Failed to get parameter: " << param_name);
00080   }
00081 
00082   return rtn;
00083 
00084 }
00085 
00086 bool getJointNames(const std::string param_name, std::vector<std::string> & joint_names)
00087 {
00088   if (ros::param::has(param_name) && getListParam(param_name, joint_names))
00089     return true;
00090 
00091   const int NUM_JOINTS = 6;  //Most robots have 6 joints
00092 
00093   joint_names.clear();
00094   for (int i=0; i<NUM_JOINTS; ++i)
00095   {
00096     std::stringstream tmp;
00097     tmp << "joint_" << i+1;
00098     joint_names.push_back(tmp.str());
00099   }
00100 
00101     return false;
00102 }
00103 
00104 bool getJointVelocityLimits(const std::string urdf_param_name, std::map<std::string, double> &velocity_limits)
00105 {
00106   urdf::Model model;
00107   std::map<std::string, boost::shared_ptr<urdf::Joint> >::iterator iter;
00108 
00109   if (!ros::param::has(urdf_param_name) || !model.initParam(urdf_param_name))
00110     return false;
00111     
00112   velocity_limits.clear();
00113   for (iter=model.joints_.begin(); iter!=model.joints_.end(); ++iter)
00114   {
00115     std::string joint_name(iter->first);
00116     boost::shared_ptr<urdf::JointLimits> limits = iter->second->limits;
00117     if ( limits && (limits->velocity > 0) )
00118       velocity_limits.insert(std::pair<std::string,double>(joint_name,limits->velocity));
00119   }
00120   
00121   return true;
00122 }
00123 
00124 } //industrial_utils::param
00125 } //industrial_utils


industrial_utils
Author(s): Shaun M. Edwards
autogenerated on Mon Oct 6 2014 00:54:49