37 #include <urdf/urdfdom_compatibility.h>
43 bool getListParam(
const std::string param_name, std::vector<std::string> & list_param)
59 for (
int i = 0; i < rpc_list.
size(); ++i)
65 list_param.push_back(
static_cast<std::string
>(rpc_list[i]));
87 std::string
vec2str(
const std::vector<std::string> &vec)
89 std::string
s, delim =
", ";
91 std::copy(vec.begin(), vec.end(), std::ostream_iterator<std::string>(ss, delim.c_str()));
93 return "[" +
s.erase(
s.length()-2) +
"]";
96 bool getJointNames(
const std::string joint_list_param,
const std::string urdf_param,
97 std::vector<std::string> & joint_names)
104 ROS_INFO_STREAM(
"Found user-specified joint names in '" << joint_list_param <<
"': " <<
vec2str(joint_names));
108 ROS_WARN_STREAM(
"Unable to find user-specified joint names in '" << joint_list_param <<
"'");
120 ROS_WARN_STREAM(
"Unable to find URDF joint names in '" << urdf_param <<
"'");
124 "Cannot find user-specified joint names. Tried ROS parameter '" << joint_list_param <<
"'"
125 <<
" and the URDF in '" << urdf_param <<
"'.");
132 std::map<std::string, urdf::JointSharedPtr >::iterator iter;
137 velocity_limits.clear();
138 for (iter=model.joints_.begin(); iter!=model.joints_.end(); ++iter)
140 std::string joint_name(iter->first);
141 urdf::JointLimitsSharedPtr limits = iter->second->limits;
142 if ( limits && (limits->velocity > 0) )
143 velocity_limits.insert(std::pair<std::string,double>(joint_name,limits->velocity));