Public Member Functions | Protected Member Functions | Static Protected Member Functions | Protected Attributes | Private Member Functions | Static Private Member Functions | Private Attributes | Friends
ddynamic_reconfigure::DDynamicReconfigure Class Reference

The DDynamicReconfigure class is the main class responsible for keeping track of parameters basic properties, values, descriptions, etc. More...

#include <ddynamic_reconfigure.h>

List of all members.

Public Member Functions

virtual void add (DDPtr param)
 adds a parameter to the list, allowing it to be generated.
virtual void add (DDParam *param)
 a convenience method for adding a parameter to the list, allowing it to be generated.
DDPtr at (const char *name)
 a tool people who use this API can use to find the param given within the param map.
void clearCallback ()
 sets the callback to be empty.
 DDynamicReconfigure (ros::NodeHandle &nh)
 creates the most basic instance of a 2d-conf object.
Value get (const char *name)
 a tool people who use this API can use to find the value given within the param map.
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.
virtual void start ()
 starts the server and config, without having any callback.
void start (DDFunc callback)
 starts the server, using the given callback in function form.
void start (void(*callback)(const DDMap &, int))
 starts the server, using the given callback in method form.
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.

Protected Member Functions

Config makeConfig ()
 makes the config update for publishing
ConfigDescription makeDescription ()
 makes the config descriptions for publishing

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.

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".
ros::NodeHandle nh_
 the ROS node handler to use to make everything ROS related.
DDMap params_
 a map of all contained parameters.
ros::Publisher update_pub_

Private Member Functions

int getUpdates (const Reconfigure::Request &req, DDMap &config)
 gets the updates and assigns them to DDMap

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.

Private Attributes

boost::shared_ptr< DDFunccallback_
 the use defined callback to call when parameters are updated.
ros::ServiceServer set_service_
 the service server used to trigger parameter updates. It also contains the new parameters sent from client or commandline.

Friends

ostream & operator<< (ostream &os, const DDynamicReconfigure &dd)
 the operator taking care of streaming the param values

Detailed Description

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:

1. Construct a DDynamicReconfigure instance with proper handling. 2. Add parameters to the instance as needed with any of the "add" methods. 3. Start the ROS services with any of the "start" methods. 4. If you need to change the callback after startup you may do so using "setCallback". 5. When you need to get any of the stored parameters, call either "get" or "at" on this instance, rather than through the callback.

Definition at line 45 of file ddynamic_reconfigure.h.


Constructor & Destructor Documentation

creates the most basic instance of a 2d-conf object.

Parameters:
nhthe node handler of the node this is placed at.

Definition at line 17 of file ddynamic_reconfigure.cpp.


Member Function Documentation

adds a parameter to the list, allowing it to be generated.

Parameters:
paramthe pointer to the 2d-param to add to the list.

Definition at line 21 of file ddynamic_reconfigure.cpp.

a convenience method for adding a parameter to the list, allowing it to be generated.

Warning:
When adding in this manner, you must be careful. After using this method to add the parameter, running any of the "remove" methods on this object WILL cause the entire param object to be deleted! To make sure that you can add the object back after removing it, please use the other "add" method.
Parameters:
paramthe pointer to the 2d-param to add to the list.

Definition at line 25 of file ddynamic_reconfigure.cpp.

a tool people who use this API can use to find the param given within the param map.

Parameters:
namethe string to look for
Returns:
the param with the given name if it exists, nullptr otherwise

Definition at line 189 of file ddynamic_reconfigure.cpp.

sets the callback to be empty.

Definition at line 108 of file ddynamic_reconfigure.cpp.

a tool people who use this API can use to find the value given within the param map.

Parameters:
namethe string to look for
Returns:
the value of param with the given name if it exists, a string value containing "\000" otherwise

Definition at line 185 of file ddynamic_reconfigure.cpp.

int ddynamic_reconfigure::DDynamicReconfigure::getUpdates ( const Reconfigure::Request &  req,
DDMap config 
) [private]

gets the updates and assigns them to DDMap

Parameters:
reqthe ROS request holding info about the new map
configthe map to update
Returns:
the level of change (integer)

Definition at line 133 of file ddynamic_reconfigure.cpp.

bool ddynamic_reconfigure::DDynamicReconfigure::internalCallback ( DDynamicReconfigure obj,
Reconfigure::Request &  req,
Reconfigure::Response &  rsp 
) [static, protected]

calls the internal callback for the low-level service, not exposed to us.

Parameters:
objthe object we are using for its callback.
req----(ROS)
rsp----(ROS)
Returns:
-------(ROS)
Note:
this is here so that deriving methods can call the internal callback.

Definition at line 113 of file ddynamic_reconfigure.cpp.

makes the config update for publishing

Returns:
a ROS message of type Config

Definition at line 58 of file ddynamic_reconfigure.cpp.

makes the config descriptions for publishing

Returns:
a ROS message of type ConfigDescription

Definition at line 72 of file ddynamic_reconfigure.cpp.

template<class T >
int ddynamic_reconfigure::DDynamicReconfigure::reassign ( DDMap map,
const string &  name,
value 
) [static, private]

reassigns a value to the internal map assuming it is registered.

Parameters:
mapthe map that is being edited
namethe name of the parameter to test
valuethe value of the new parameter
Template Parameters:
Tthe type of value
Returns:
-1 if the value could not be reassigned, 0 if the value was not changed, otherwise the level of the parameter changed.

Definition at line 172 of file ddynamic_reconfigure.cpp.

removes the specified parameter from the list.

Parameters:
paramthe parameter to remove.

Definition at line 29 of file ddynamic_reconfigure.cpp.

removes the specified parameter from the list.

Parameters:
paramthe parameter to remove.

Definition at line 33 of file ddynamic_reconfigure.cpp.

void ddynamic_reconfigure::DDynamicReconfigure::remove ( string  param_name) [virtual]

removes the specified parameter from the list.

Parameters:
param_namethe name of the parameter to remove.

Definition at line 37 of file ddynamic_reconfigure.cpp.

sets the callback to this.

Parameters:
callbacka boost function with the method to use when values are updated.

Definition at line 102 of file ddynamic_reconfigure.cpp.

starts the server and config, without having any callback.

Definition at line 41 of file ddynamic_reconfigure.cpp.

starts the server, using the given callback in function form.

Parameters:
callbacka 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.

Parameters:
callbacka void pointer accepting a callback type with the method to use when values are updated.

Definition at line 91 of file ddynamic_reconfigure.cpp.

template<class T >
void ddynamic_reconfigure::DDynamicReconfigure::start ( void(T::*)(const DDMap &, int)  callback,
T *  obj 
) [inline]

starts the server, using the given callback in class-wise static method form.

Parameters:
callbacka class void pointer accepting a callback type with the method to use when values are updated.
objthe object used for reference in the class void
Template Parameters:
Tthe class of the object.

Definition at line 121 of file ddynamic_reconfigure.h.


Friends And Related Function Documentation

ostream& operator<< ( ostream &  os,
const DDynamicReconfigure dd 
) [friend]

the operator taking care of streaming the param values

Parameters:
osthe stream to place the param into
ddthe dd-reconfigure you want to place into the stream
Returns:
os, but with dd-reconfigure added.

Definition at line 193 of file ddynamic_reconfigure.cpp.


Member Data Documentation

the use defined callback to call when parameters are updated.

Definition at line 212 of file ddynamic_reconfigure.h.

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.

the ROS node handler to use to make everything ROS related.

Definition at line 174 of file ddynamic_reconfigure.h.

a map of all contained parameters.

Definition at line 178 of file ddynamic_reconfigure.h.

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.

Definition at line 184 of file ddynamic_reconfigure.h.


The documentation for this class was generated from the following files:


ddynamic_reconfigure
Author(s): Noam Dori
autogenerated on Wed May 15 2019 04:39:27