29 #ifndef ROSCPP_PARAM_H
30 #define ROSCPP_PARAM_H
34 #include "xmlrpcpp/XmlRpcValue.h"
98 ROSCPP_DECL void set(
const std::string& key,
const std::vector<std::string>& vec);
105 ROSCPP_DECL void set(
const std::string& key,
const std::vector<double>& vec);
112 ROSCPP_DECL void set(
const std::string& key,
const std::vector<float>& vec);
119 ROSCPP_DECL void set(
const std::string& key,
const std::vector<int>& vec);
126 ROSCPP_DECL void set(
const std::string& key,
const std::vector<bool>& vec);
134 ROSCPP_DECL void set(
const std::string& key,
const std::map<std::string, std::string>& map);
141 ROSCPP_DECL void set(
const std::string& key,
const std::map<std::string, double>& map);
148 ROSCPP_DECL void set(
const std::string& key,
const std::map<std::string, float>& map);
155 ROSCPP_DECL void set(
const std::string& key,
const std::map<std::string, int>& map);
162 ROSCPP_DECL void set(
const std::string& key,
const std::map<std::string, bool>& map);
313 ROSCPP_DECL bool get(
const std::string& key, std::vector<std::string>& vec);
322 ROSCPP_DECL bool get(
const std::string& key, std::vector<double>& vec);
331 ROSCPP_DECL bool get(
const std::string& key, std::vector<float>& vec);
340 ROSCPP_DECL bool get(
const std::string& key, std::vector<int>& vec);
349 ROSCPP_DECL bool get(
const std::string& key, std::vector<bool>& vec);
430 ROSCPP_DECL bool get(
const std::string& key, std::map<std::string, std::string>& map);
439 ROSCPP_DECL bool get(
const std::string& key, std::map<std::string, double>& map);
448 ROSCPP_DECL bool get(
const std::string& key, std::map<std::string, float>& map);
457 ROSCPP_DECL bool get(
const std::string& key, std::map<std::string, int>& map);
466 ROSCPP_DECL bool get(
const std::string& key, std::map<std::string, bool>& map);
570 ROSCPP_DECL bool search(
const std::string& ns,
const std::string& key, std::string& result);
609 bool param(
const std::string& param_name, T& param_val,
const T& default_val)
613 if (
get(param_name, param_val))
619 param_val = default_val;
641 T
param(
const std::string& param_name,
const T& default_val)
644 param(param_name, param_val, default_val);
652 #endif // ROSCPP_PARAM_H