Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
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();
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;
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 }
00125 }