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 #ifndef ROSPARAM_SHORTCUTS_ROSPARAM_SHORTCUTS_H
00040 #define ROSPARAM_SHORTCUTS_ROSPARAM_SHORTCUTS_H
00041
00042
00043 #include <string>
00044 #include <vector>
00045 #include <map>
00046
00047
00048 #include <ros/ros.h>
00049
00050
00051 #include <Eigen/Geometry>
00052
00053
00054 #include <rosparam_shortcuts/deprecation.h>
00055
00056 namespace rosparam_shortcuts
00057 {
00058
00059
00060
00061
00071 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, bool &value);
00072
00073 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶ms_name,
00074 std::map<std::string, bool> ¶meters);
00075
00076 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, double &value);
00077
00078 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00079 std::vector<double> &values);
00080
00081 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, int &value);
00082
00083 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::size_t &value);
00084
00085 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, std::string &value);
00086
00087 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00088 std::vector<std::string> &values);
00089
00090 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00091 ros::Duration &value);
00092
00093 bool get(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00094 Eigen::Affine3d &value);
00095
00096
00097
00098
00099
00100 ROSPARAM_SHORTCUTS_DEPRECATED
00101 bool getBoolParam(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, bool &value)
00102 {
00103 return get(parent_name, nh, param_name, value);
00104 }
00105
00106 ROSPARAM_SHORTCUTS_DEPRECATED
00107 bool getBoolMap(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶ms_name,
00108 std::map<std::string, bool> ¶meters)
00109 {
00110 return get(parent_name, nh, params_name, parameters);
00111 }
00112
00113 ROSPARAM_SHORTCUTS_DEPRECATED
00114 bool getDoubleParam(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00115 double &value)
00116 {
00117 return get(parent_name, nh, param_name, value);
00118 }
00119
00120 ROSPARAM_SHORTCUTS_DEPRECATED
00121 bool getDoubleParams(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00122 std::vector<double> &values)
00123 {
00124 return get(parent_name, nh, param_name, values);
00125 }
00126
00127 ROSPARAM_SHORTCUTS_DEPRECATED
00128 bool getIntParam(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name, int &value)
00129 {
00130 return get(parent_name, nh, param_name, value);
00131 }
00132
00133 ROSPARAM_SHORTCUTS_DEPRECATED
00134 bool getSizeTParam(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00135 std::size_t &value)
00136 {
00137 return get(parent_name, nh, param_name, value);
00138 }
00139
00140 ROSPARAM_SHORTCUTS_DEPRECATED
00141 bool getStringParam(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00142 std::string &value)
00143 {
00144 return get(parent_name, nh, param_name, value);
00145 }
00146
00147 ROSPARAM_SHORTCUTS_DEPRECATED
00148 bool getStringParams(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00149 std::vector<std::string> &values)
00150 {
00151 return get(parent_name, nh, param_name, values);
00152 }
00153
00154 ROSPARAM_SHORTCUTS_DEPRECATED
00155 bool getDurationParam(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00156 ros::Duration &value)
00157 {
00158 return get(parent_name, nh, param_name, value);
00159 }
00160
00161 ROSPARAM_SHORTCUTS_DEPRECATED
00162 bool getAffine3dParam(const std::string &parent_name, const ros::NodeHandle &nh, const std::string ¶m_name,
00163 Eigen::Affine3d &value)
00164 {
00165 return get(parent_name, nh, param_name, value);
00166 }
00167
00173 std::string getDebugArrayString(std::vector<double> values);
00174
00175 std::string getDebugArrayString(std::vector<std::string> values);
00176
00181 bool convertDoublesToEigen(const std::string &parent_name, std::vector<double> values, Eigen::Affine3d &transform);
00182
00187 void shutdownIfError(const std::string &parent_name, std::size_t error_count);
00188
00189 ROSPARAM_SHORTCUTS_DEPRECATED
00190 void shutdownIfParamErrors(const std::string &parent_name, std::size_t error_count)
00191 {
00192 shutdownIfError(parent_name, error_count);
00193 }
00194
00195 }
00196
00197 #endif // ROSPARAM_SHORTCUTS_ROSPARAM_SHORTCUTS_H