28 #ifndef ROSCPP_PARAM_H
29 #define ROSCPP_PARAM_H
60 ROSCPP_DECL
void set(
const std::string& key,
const std::string&
s);
67 ROSCPP_DECL
void set(
const std::string& key,
const char*
s);
74 ROSCPP_DECL
void set(
const std::string& key,
double d);
81 ROSCPP_DECL
void set(
const std::string& key,
int i);
88 ROSCPP_DECL
void set(
const std::string& key,
bool b);
97 ROSCPP_DECL
void set(
const std::string& key,
const std::vector<std::string>& vec);
104 ROSCPP_DECL
void set(
const std::string& key,
const std::vector<double>& vec);
111 ROSCPP_DECL
void set(
const std::string& key,
const std::vector<float>& vec);
118 ROSCPP_DECL
void set(
const std::string& key,
const std::vector<int>& vec);
125 ROSCPP_DECL
void set(
const std::string& key,
const std::vector<bool>& vec);
133 ROSCPP_DECL
void set(
const std::string& key,
const std::map<std::string, std::string>& map);
140 ROSCPP_DECL
void set(
const std::string& key,
const std::map<std::string, double>& map);
147 ROSCPP_DECL
void set(
const std::string& key,
const std::map<std::string, float>& map);
154 ROSCPP_DECL
void set(
const std::string& key,
const std::map<std::string, int>& map);
161 ROSCPP_DECL
void set(
const std::string& key,
const std::map<std::string, bool>& map);
172 ROSCPP_DECL
bool get(
const std::string& key, std::string&
s);
181 ROSCPP_DECL
bool get(
const std::string& key,
double&
d);
190 ROSCPP_DECL
bool get(
const std::string& key,
float&
f);
199 ROSCPP_DECL
bool get(
const std::string& key,
int& i);
208 ROSCPP_DECL
bool get(
const std::string& key,
bool& b);
232 ROSCPP_DECL
bool getCached(
const std::string& key, std::string&
s);
246 ROSCPP_DECL
bool getCached(
const std::string& key,
double&
d);
260 ROSCPP_DECL
bool getCached(
const std::string& key,
float&
f);
274 ROSCPP_DECL
bool getCached(
const std::string& key,
int& i);
288 ROSCPP_DECL
bool getCached(
const std::string& key,
bool& b);
312 ROSCPP_DECL
bool get(
const std::string& key, std::vector<std::string>& vec);
321 ROSCPP_DECL
bool get(
const std::string& key, std::vector<double>& vec);
330 ROSCPP_DECL
bool get(
const std::string& key, std::vector<float>& vec);
339 ROSCPP_DECL
bool get(
const std::string& key, std::vector<int>& vec);
348 ROSCPP_DECL
bool get(
const std::string& key, std::vector<bool>& vec);
363 ROSCPP_DECL
bool getCached(
const std::string& key, std::vector<std::string>& vec);
377 ROSCPP_DECL
bool getCached(
const std::string& key, std::vector<double>& vec);
391 ROSCPP_DECL
bool getCached(
const std::string& key, std::vector<float>& vec);
405 ROSCPP_DECL
bool getCached(
const std::string& key, std::vector<int>& vec);
419 ROSCPP_DECL
bool getCached(
const std::string& key, std::vector<bool>& vec);
429 ROSCPP_DECL
bool get(
const std::string& key, std::map<std::string, std::string>& map);
438 ROSCPP_DECL
bool get(
const std::string& key, std::map<std::string, double>& map);
447 ROSCPP_DECL
bool get(
const std::string& key, std::map<std::string, float>& map);
456 ROSCPP_DECL
bool get(
const std::string& key, std::map<std::string, int>& map);
465 ROSCPP_DECL
bool get(
const std::string& key, std::map<std::string, bool>& map);
480 ROSCPP_DECL
bool getCached(
const std::string& key, std::map<std::string, std::string>& map);
494 ROSCPP_DECL
bool getCached(
const std::string& key, std::map<std::string, double>& map);
508 ROSCPP_DECL
bool getCached(
const std::string& key, std::map<std::string, float>& map);
522 ROSCPP_DECL
bool getCached(
const std::string& key, std::map<std::string, int>& map);
536 ROSCPP_DECL
bool getCached(
const std::string& key, std::map<std::string, bool>& map);
545 ROSCPP_DECL
bool has(
const std::string& key);
553 ROSCPP_DECL
bool del(
const std::string& key);
569 ROSCPP_DECL
bool search(
const std::string& ns,
const std::string& key, std::string& result);
585 ROSCPP_DECL
bool search(
const std::string& key, std::string& result);
592 ROSCPP_DECL
bool getParamNames(std::vector<std::string>& keys);
619 bool param(
const std::string& param_name, T& param_val,
const T& default_val)
623 if (
get(param_name, param_val))
629 param_val = default_val;
651 T
param(
const std::string& param_name,
const T& default_val)
654 param(param_name, param_val, default_val);
662 #endif // ROSCPP_PARAM_H