19 #ifndef FF_UTIL_CONFIG_SERVER_H_
20 #define FF_UTIL_CONFIG_SERVER_H_
28 #include <dynamic_reconfigure/Reconfigure.h>
29 #include <dynamic_reconfigure/Config.h>
30 #include <dynamic_reconfigure/ConfigDescription.h>
32 #include <diagnostic_msgs/KeyValue.h>
43 typedef boost::function<bool(dynamic_reconfigure::Config &request)>
ConfigCallback;
51 void Initialize(ros::NodeHandle *private_nh,
const std::string &fname);
53 void SetPath(
const std::string &pname);
55 void AddFile(
const std::string &fname);
60 template<
typename T>
bool Get(
const std::string &
name, T &value);
61 template<
typename T>
bool Set(
const std::string &
name,
const T &value);
62 template<
typename T> T
Get(
const std::string &
name) {
65 ROS_ERROR_STREAM(
"Cannot query parameter " <<
name);
70 template<
typename T>
bool Lim(
const std::string &
name,
const std::map<T, std::string> &vals);
72 std::vector<diagnostic_msgs::KeyValue>
Dump();
76 bool Reconfigure(dynamic_reconfigure::Config &request);
80 dynamic_reconfigure::ConfigDescription UpdateDescription();
81 dynamic_reconfigure::Config UpdateValues();
83 std::string EditMethod(
const std::map<std::string, std::string> &values,
84 const std::string &ctype,
const std::string &cpptype,
const std::string &cconsttype);
86 bool ReconfigureImpl(dynamic_reconfigure::Reconfigure::Request &req, dynamic_reconfigure::Reconfigure::Response &res);
88 static bool Update(
const std::string &ns,
const dynamic_reconfigure::ReconfigureRequest &request);
92 ros::Publisher pub_d_;
93 ros::Publisher pub_u_;
94 ros::ServiceServer srv_r_;
97 std::map<std::string, bool> bools_;
98 std::map<std::string, int> ints_;
99 std::map<std::string, double> doubles_;
100 std::map<std::string, std::string> strs_;
101 dynamic_reconfigure::ConfigDescription description_;
104 template<>
bool ConfigServer::Get<int>(
const std::string &
name,
int &value);
105 template<>
bool ConfigServer::Get<double>(
const std::string &
name,
double &value);
106 template<>
bool ConfigServer::Get<bool>(
const std::string &
name,
bool &value);
107 template<>
bool ConfigServer::Get<std::string>(
const std::string &
name, std::string &value);
109 template<>
bool ConfigServer::Set<int>(
const std::string &
name,
const int &value);
110 template<>
bool ConfigServer::Set<double>(
const std::string &
name,
const double &value);
111 template<>
bool ConfigServer::Set<bool>(
const std::string &
name,
const bool &value);
112 template<>
bool ConfigServer::Set<std::string>(
const std::string &
name,
const std::string &value);
114 template<>
bool ConfigServer::Lim<int>(
const std::string &
name,
const std::map<int, std::string> &vals);
115 template<>
bool ConfigServer::Lim<double>(
const std::string &
name,
const std::map<double, std::string> &vals);
116 template<>
bool ConfigServer::Lim<bool>(
const std::string &
name,
const std::map<bool, std::string> &vals);
117 template<>
bool ConfigServer::Lim<std::string>(
const std::string &
name,
const std::map<std::string, std::string> &vals);
122 #endif // FF_UTIL_CONFIG_SERVER_H_