49 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name,
bool &value)
52 if (!nh.hasParam(param_name))
54 ROS_ERROR_STREAM_NAMED(parent_name,
"Missing parameter '" << nh.getNamespace() <<
"/" << param_name <<
"'.");
57 nh.getParam(param_name, value);
58 ROS_DEBUG_STREAM_NAMED(parent_name,
"Loaded parameter '" << nh.getNamespace() <<
"/" << param_name <<
"' with value " 64 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶ms_namespace,
65 std::map<std::string, bool> ¶meters)
68 if (!nh.hasParam(params_namespace))
71 << params_namespace <<
"'.");
74 nh.getParam(params_namespace, parameters);
77 for (std::map<std::string, bool>::const_iterator param_it = parameters.begin(); param_it != parameters.end();
80 ROS_DEBUG_STREAM_NAMED(parent_name,
"Loaded parameter '" << nh.getNamespace() <<
"/" << params_namespace <<
"/" 81 << param_it->first <<
"' with value " << param_it->second);
87 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name,
double &value)
90 if (!nh.hasParam(param_name))
92 ROS_ERROR_STREAM_NAMED(parent_name,
"Missing parameter '" << nh.getNamespace() <<
"/" << param_name <<
"'.");
95 nh.getParam(param_name, value);
96 ROS_DEBUG_STREAM_NAMED(parent_name,
"Loaded parameter '" << nh.getNamespace() <<
"/" << param_name <<
"' with value " 102 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name,
103 std::vector<double> &values)
106 if (!nh.hasParam(param_name))
108 ROS_ERROR_STREAM_NAMED(parent_name,
"Missing parameter '" << nh.getNamespace() <<
"/" << param_name <<
"'.");
111 nh.getParam(param_name, values);
114 ROS_WARN_STREAM_NAMED(parent_name,
"Empty vector for parameter '" << nh.getNamespace() <<
"/" << param_name <<
"'" 123 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name,
int &value)
126 if (!nh.hasParam(param_name))
128 ROS_ERROR_STREAM_NAMED(parent_name,
"Missing parameter '" << nh.getNamespace() <<
"/" << param_name <<
"'.");
131 nh.getParam(param_name, value);
132 ROS_DEBUG_STREAM_NAMED(parent_name,
"Loaded parameter '" << nh.getNamespace() <<
"/" << param_name <<
"' with value " 138 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name, std::size_t &value)
141 if (!nh.hasParam(param_name))
143 ROS_ERROR_STREAM_NAMED(parent_name,
"Missing parameter '" << nh.getNamespace() <<
"/" << param_name <<
"'.");
147 nh.getParam(param_name, nonsigned_value);
148 value = nonsigned_value;
149 ROS_DEBUG_STREAM_NAMED(parent_name,
"Loaded parameter '" << nh.getNamespace() <<
"/" << param_name <<
"' with value " 155 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name, std::string &value)
158 if (!nh.hasParam(param_name))
160 ROS_ERROR_STREAM_NAMED(parent_name,
"Missing parameter '" << nh.getNamespace() <<
"/" << param_name <<
"'.");
163 nh.getParam(param_name, value);
164 ROS_DEBUG_STREAM_NAMED(parent_name,
"Loaded parameter '" << nh.getNamespace() <<
"/" << param_name <<
"' with value " 170 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name,
171 std::vector<std::string> &values)
174 if (!nh.hasParam(param_name))
176 ROS_ERROR_STREAM_NAMED(parent_name,
"Missing parameter '" << nh.getNamespace() <<
"/" << param_name <<
"'.");
179 nh.getParam(param_name, values);
182 ROS_WARN_STREAM_NAMED(parent_name,
"Empty vector for parameter '" << nh.getNamespace() <<
"/" << param_name <<
"'" 185 ROS_DEBUG_STREAM_NAMED(parent_name,
"Loaded parameter '" << nh.getNamespace() <<
"/" << param_name <<
"' with value " 195 if (!nh.hasParam(param_name))
197 ROS_ERROR_STREAM_NAMED(parent_name,
"Missing parameter '" << nh.getNamespace() <<
"/" << param_name <<
"'.");
200 nh.getParam(param_name, temp_value);
201 ROS_DEBUG_STREAM_NAMED(parent_name,
"Loaded parameter '" << nh.getNamespace() <<
"/" << param_name <<
"' with value " 210 bool get(
const std::string &parent_name,
const ros::NodeHandle &nh,
const std::string ¶m_name,
211 Eigen::Affine3d &value)
213 std::vector<double> values;
216 if (!nh.hasParam(param_name))
218 ROS_ERROR_STREAM_NAMED(parent_name,
"Missing parameter '" << nh.getNamespace() <<
"/" << param_name <<
"'.");
221 nh.getParam(param_name, values);
224 ROS_WARN_STREAM_NAMED(parent_name,
"Empty vector for parameter '" << nh.getNamespace() <<
"/" << param_name <<
"'" 238 std::stringstream debug_values;
239 for (std::size_t i = 0; i < values.size(); ++i)
241 debug_values << values[i] <<
",";
243 return debug_values.str();
248 std::stringstream debug_values;
249 for (std::size_t i = 0; i < values.size(); ++i)
251 debug_values << values[i] <<
",";
253 return debug_values.str();
258 if (values.size() == 6)
261 Eigen::AngleAxisd roll_angle(values[3], Eigen::Vector3d::UnitX());
262 Eigen::AngleAxisd pitch_angle(values[4], Eigen::Vector3d::UnitY());
263 Eigen::AngleAxisd yaw_angle(values[5], Eigen::Vector3d::UnitZ());
264 Eigen::Quaternion<double> quaternion = roll_angle * pitch_angle * yaw_angle;
266 transform = Eigen::Translation3d(values[0], values[1], values[2]) * quaternion;
270 else if (values.size() == 7)
273 transform = Eigen::Translation3d(values[0], values[1], values[2]) *
274 Eigen::Quaterniond(values[3], values[4], values[5], values[6]);
279 ROS_ERROR_STREAM_NAMED(parent_name,
"Invalid number of doubles provided for transform, size=" << values.size());
289 ROS_ERROR_STREAM_NAMED(parent_name,
"Missing " << error_count <<
" ros parameters that are required. Shutting down " 290 "to prevent undefined behaviors");
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
bool convertDoublesToEigen(const std::string &parent_name, std::vector< double > values, Eigen::Affine3d &transform)
Convert from 6 doubles of [x,y,z] [r,p,y] or 7 doubles of [x, y, z, qw, qx, qy, qz] to a transform...
void shutdownIfError(const std::string &parent_name, std::size_t error_count)
Check that there were no errors, and if there were, shutdown.
ROSCPP_DECL void shutdown()
std::string getDebugArrayString(std::vector< double > values)
Output a string of values from an array for debugging.
#define ROS_WARN_STREAM_NAMED(name, args)