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
00033
00034
00035
00036
00037
00038
00039
00040 #include <string>
00041 #include <vector>
00042 #include <map>
00043
00044
00045 #include <rosparam_shortcuts/rosparam_shortcuts.h>
00046
00047 namespace rosparam_shortcuts
00048 {
00049 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, bool &value)
00050 {
00051
00052 if (!nh.hasParam(param_name))
00053 {
00054 ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'.");
00055 return false;
00056 }
00057 nh.getParam(param_name, value);
00058 ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name << "' with value "
00059 << value);
00060
00061 return true;
00062 }
00063
00064 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶ms_namespace,
00065 std::map<std::string, bool> ¶meters)
00066 {
00067
00068 if (!nh.hasParam(params_namespace))
00069 {
00070 ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameters in namespace '" << nh.getNamespace() << "/"
00071 << params_namespace << "'.");
00072 return false;
00073 }
00074 nh.getParam(params_namespace, parameters);
00075
00076
00077 for (std::map<std::string, bool>::const_iterator param_it = parameters.begin(); param_it != parameters.end();
00078 param_it++)
00079 {
00080 ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << params_namespace << "/"
00081 << param_it->first << "' with value " << param_it->second);
00082 }
00083
00084 return true;
00085 }
00086
00087 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, double &value)
00088 {
00089
00090 if (!nh.hasParam(param_name))
00091 {
00092 ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'.");
00093 return false;
00094 }
00095 nh.getParam(param_name, value);
00096 ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name << "' with value "
00097 << value);
00098
00099 return true;
00100 }
00101
00102 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00103 std::vector<double> &values)
00104 {
00105
00106 if (!nh.hasParam(param_name))
00107 {
00108 ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'.");
00109 return false;
00110 }
00111 nh.getParam(param_name, values);
00112
00113 if (values.empty())
00114 ROS_WARN_STREAM_NAMED(parent_name, "Empty vector for parameter '" << nh.getNamespace() << "/" << param_name << "'"
00115 ".");
00116
00117 ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name
00118 << "' with values [" << getDebugArrayString(values) << "]");
00119
00120 return true;
00121 }
00122
00123 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, int &value)
00124 {
00125
00126 if (!nh.hasParam(param_name))
00127 {
00128 ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'.");
00129 return false;
00130 }
00131 nh.getParam(param_name, value);
00132 ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name << "' with value "
00133 << value);
00134
00135 return true;
00136 }
00137
00138 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::size_t &value)
00139 {
00140
00141 if (!nh.hasParam(param_name))
00142 {
00143 ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'.");
00144 return false;
00145 }
00146 int nonsigned_value;
00147 nh.getParam(param_name, nonsigned_value);
00148 value = nonsigned_value;
00149 ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name << "' with value "
00150 << value);
00151
00152 return true;
00153 }
00154
00155 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::string &value)
00156 {
00157
00158 if (!nh.hasParam(param_name))
00159 {
00160 ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'.");
00161 return false;
00162 }
00163 nh.getParam(param_name, value);
00164 ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name << "' with value "
00165 << value);
00166
00167 return true;
00168 }
00169
00170 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00171 std::vector<std::string> &values)
00172 {
00173
00174 if (!nh.hasParam(param_name))
00175 {
00176 ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'.");
00177 return false;
00178 }
00179 nh.getParam(param_name, values);
00180
00181 if (values.empty())
00182 ROS_WARN_STREAM_NAMED(parent_name, "Empty vector for parameter '" << nh.getNamespace() << "/" << param_name << "'"
00183 ".");
00184
00185 ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name << "' with value "
00186 << getDebugArrayString(values));
00187
00188 return true;
00189 }
00190
00191 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, ros::Duration &value)
00192 {
00193 double temp_value;
00194
00195 if (!nh.hasParam(param_name))
00196 {
00197 ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'.");
00198 return false;
00199 }
00200 nh.getParam(param_name, temp_value);
00201 ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name << "' with value "
00202 << value);
00203
00204
00205 value = ros::Duration(temp_value);
00206
00207 return true;
00208 }
00209
00210 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00211 Eigen::Affine3d &value)
00212 {
00213 std::vector<double> values;
00214
00215
00216 if (!nh.hasParam(param_name))
00217 {
00218 ROS_ERROR_STREAM_NAMED(parent_name, "Missing parameter '" << nh.getNamespace() << "/" << param_name << "'.");
00219 return false;
00220 }
00221 nh.getParam(param_name, values);
00222
00223 if (values.empty())
00224 ROS_WARN_STREAM_NAMED(parent_name, "Empty vector for parameter '" << nh.getNamespace() << "/" << param_name << "'"
00225 ".");
00226
00227 ROS_DEBUG_STREAM_NAMED(parent_name, "Loaded parameter '" << nh.getNamespace() << "/" << param_name
00228 << "' with values [" << getDebugArrayString(values) << "]");
00229
00230
00231 convertDoublesToEigen(parent_name, values, value);
00232
00233 return true;
00234 }
00235
00236 std::string getDebugArrayString(std::vector<double> values)
00237 {
00238 std::stringstream debug_values;
00239 for (std::size_t i = 0; i < values.size(); ++i)
00240 {
00241 debug_values << values[i] << ",";
00242 }
00243 return debug_values.str();
00244 }
00245
00246 std::string getDebugArrayString(std::vector<std::string> values)
00247 {
00248 std::stringstream debug_values;
00249 for (std::size_t i = 0; i < values.size(); ++i)
00250 {
00251 debug_values << values[i] << ",";
00252 }
00253 return debug_values.str();
00254 }
00255
00256 bool convertDoublesToEigen(const std::string &parent_name, std::vector<double> values, Eigen::Affine3d &transform)
00257 {
00258 if (values.size() != 6)
00259 {
00260 ROS_ERROR_STREAM_NAMED(parent_name, "Invalid number of doubles provided for transform, size=" << values.size());
00261 return false;
00262 }
00263
00264
00265 Eigen::AngleAxisd roll_angle(values[3], Eigen::Vector3d::UnitX());
00266 Eigen::AngleAxisd pitch_angle(values[4], Eigen::Vector3d::UnitY());
00267 Eigen::AngleAxisd yaw_angle(values[5], Eigen::Vector3d::UnitZ());
00268 Eigen::Quaternion<double> quaternion = roll_angle * pitch_angle * yaw_angle;
00269
00270 transform = Eigen::Translation3d(values[0], values[1], values[2]) * quaternion;
00271
00272 return true;
00273 }
00274
00275 void shutdownIfError(const std::string &parent_name, std::size_t error_count)
00276 {
00277 if (!error_count)
00278 return;
00279
00280 ROS_ERROR_STREAM_NAMED(parent_name, "Missing " << error_count << " ros parameters that are required. Shutting down "
00281 "to prevent undefined behaviors");
00282 ros::shutdown();
00283 exit(0);
00284 }
00285
00286 }