The DDynamicReconfigure class is the main class responsible for keeping track of parameters basic properties, values, descriptions, etc. More...
#include <ddynamic_reconfigure.h>
Public Member Functions | |
virtual void | add (DDPtr param) |
adds a parameter to the list, allowing it to be generated. More... | |
virtual void | add (DDParam *param) |
a convenience method for adding a parameter to the list, allowing it to be generated. More... | |
DDPtr | at (const char *name) |
a tool people who use this API can use to find the param given within the param map. More... | |
void | clearCallback () |
sets the callback to be empty. More... | |
DDynamicReconfigure (ros::NodeHandle &nh) | |
creates the most basic instance of a 2d-conf object. More... | |
Value | get (const char *name) |
a tool people who use this API can use to find the value given within the param map. More... | |
virtual void | remove (DDPtr param) |
virtual void | remove (DDParam *param) |
virtual void | remove (string param_name) |
void | setCallback (DDFunc callback) |
sets the callback to this. More... | |
virtual void | start () |
starts the server and config, without having any callback. More... | |
void | start (DDFunc callback) |
starts the server, using the given callback in function form. More... | |
void | start (void(*callback)(const DDMap &, int)) |
starts the server, using the given callback in method form. More... | |
template<class T > | |
void | start (void(T::*callback)(const DDMap &, int), T *obj) |
starts the server, using the given callback in class-wise static method form. More... | |
Protected Member Functions | |
Config | makeConfig () |
makes the config update for publishing More... | |
ConfigDescription | makeDescription () |
makes the config descriptions for publishing More... | |
Static Protected Member Functions | |
static bool | internalCallback (DDynamicReconfigure *obj, Reconfigure::Request &req, Reconfigure::Response &rsp) |
calls the internal callback for the low-level service, not exposed to us. More... | |
Protected Attributes | |
ros::Publisher | desc_pub_ |
the publisher responsible for updating the descriptions of the parameter for commandline (desc_pub_), and the publisher responsible for updating the configuration values for commandline and client (update_pub_). desc_pub_ publishes to "parameter_descriptions", and update_pub_ publishes to "/parameter_updates". More... | |
ros::NodeHandle | nh_ |
the ROS node handler to use to make everything ROS related. More... | |
DDMap | params_ |
a map of all contained parameters. More... | |
ros::Publisher | update_pub_ |
Private Member Functions | |
int | getUpdates (const Reconfigure::Request &req, DDMap &config) |
gets the updates and assigns them to DDMap More... | |
Static Private Member Functions | |
template<class T > | |
static int | reassign (DDMap &map, const string &name, T value) |
reassigns a value to the internal map assuming it is registered. More... | |
Private Attributes | |
boost::shared_ptr< DDFunc > | callback_ |
the use defined callback to call when parameters are updated. More... | |
ros::ServiceServer | set_service_ |
the service server used to trigger parameter updates. It also contains the new parameters sent from client or commandline. More... | |
Friends | |
ostream & | operator<< (ostream &os, const DDynamicReconfigure &dd) |
the operator taking care of streaming the param values More... | |
The DDynamicReconfigure class is the main class responsible for keeping track of parameters basic properties, values, descriptions, etc.
It is also responsible of handling callbacks, config change requests, description setup and config setup, and the ROS publishers and services.
To operate a DDynamic instance, you must go through the following procedure:
Definition at line 45 of file ddynamic_reconfigure.h.
|
explicit |
creates the most basic instance of a 2d-conf object.
nh | the node handler of the node this is placed at. |
Definition at line 17 of file ddynamic_reconfigure.cpp.
|
virtual |
adds a parameter to the list, allowing it to be generated.
param | the pointer to the 2d-param to add to the list. |
Definition at line 21 of file ddynamic_reconfigure.cpp.
|
virtual |
a convenience method for adding a parameter to the list, allowing it to be generated.
param | the pointer to the 2d-param to add to the list. |
Definition at line 25 of file ddynamic_reconfigure.cpp.
DDPtr ddynamic_reconfigure::DDynamicReconfigure::at | ( | const char * | name | ) |
a tool people who use this API can use to find the param given within the param map.
name | the string to look for |
Definition at line 189 of file ddynamic_reconfigure.cpp.
void ddynamic_reconfigure::DDynamicReconfigure::clearCallback | ( | ) |
sets the callback to be empty.
Definition at line 108 of file ddynamic_reconfigure.cpp.
Value ddynamic_reconfigure::DDynamicReconfigure::get | ( | const char * | name | ) |
a tool people who use this API can use to find the value given within the param map.
name | the string to look for |
Definition at line 185 of file ddynamic_reconfigure.cpp.
|
private |
gets the updates and assigns them to DDMap
req | the ROS request holding info about the new map |
config | the map to update |
Definition at line 133 of file ddynamic_reconfigure.cpp.
|
staticprotected |
calls the internal callback for the low-level service, not exposed to us.
obj | the object we are using for its callback. |
req | -—(ROS) |
rsp | -—(ROS) |
Definition at line 113 of file ddynamic_reconfigure.cpp.
|
protected |
makes the config update for publishing
Definition at line 58 of file ddynamic_reconfigure.cpp.
|
protected |
makes the config descriptions for publishing
Definition at line 72 of file ddynamic_reconfigure.cpp.
|
staticprivate |
reassigns a value to the internal map assuming it is registered.
map | the map that is being edited |
name | the name of the parameter to test |
value | the value of the new parameter |
T | the type of value |
Definition at line 172 of file ddynamic_reconfigure.cpp.
|
virtual |
removes the specified parameter from the list.
param | the parameter to remove. |
Definition at line 29 of file ddynamic_reconfigure.cpp.
|
virtual |
removes the specified parameter from the list.
param | the parameter to remove. |
Definition at line 33 of file ddynamic_reconfigure.cpp.
|
virtual |
removes the specified parameter from the list.
param_name | the name of the parameter to remove. |
Definition at line 37 of file ddynamic_reconfigure.cpp.
void ddynamic_reconfigure::DDynamicReconfigure::setCallback | ( | DDFunc | callback | ) |
sets the callback to this.
callback | a boost function with the method to use when values are updated. |
Definition at line 102 of file ddynamic_reconfigure.cpp.
|
virtual |
starts the server and config, without having any callback.
Definition at line 41 of file ddynamic_reconfigure.cpp.
void ddynamic_reconfigure::DDynamicReconfigure::start | ( | DDFunc | callback | ) |
starts the server, using the given callback in function form.
callback | a boost function with the method to use when values are updated. |
Definition at line 86 of file ddynamic_reconfigure.cpp.
void ddynamic_reconfigure::DDynamicReconfigure::start | ( | void(*)(const DDMap &, int) | callback | ) |
starts the server, using the given callback in method form.
callback | a void pointer accepting a callback type with the method to use when values are updated. |
Definition at line 91 of file ddynamic_reconfigure.cpp.
|
inline |
starts the server, using the given callback in class-wise static method form.
callback | a class void pointer accepting a callback type with the method to use when values are updated. |
obj | the object used for reference in the class void |
T | the class of the object. |
Definition at line 121 of file ddynamic_reconfigure.h.
|
friend |
the operator taking care of streaming the param values
os | the stream to place the param into |
dd | the dd-reconfigure you want to place into the stream |
Definition at line 193 of file ddynamic_reconfigure.cpp.
|
private |
the use defined callback to call when parameters are updated.
Definition at line 212 of file ddynamic_reconfigure.h.
|
protected |
the publisher responsible for updating the descriptions of the parameter for commandline (desc_pub_), and the publisher responsible for updating the configuration values for commandline and client (update_pub_). desc_pub_ publishes to "parameter_descriptions", and update_pub_ publishes to "/parameter_updates".
Definition at line 184 of file ddynamic_reconfigure.h.
|
protected |
the ROS node handler to use to make everything ROS related.
Definition at line 174 of file ddynamic_reconfigure.h.
|
protected |
a map of all contained parameters.
Definition at line 178 of file ddynamic_reconfigure.h.
|
private |
the service server used to trigger parameter updates. It also contains the new parameters sent from client or commandline.
Definition at line 221 of file ddynamic_reconfigure.h.
|
protected |
Definition at line 184 of file ddynamic_reconfigure.h.