#include <client.h>
Public Member Functions | |
| Client (const std::string &name, const ros::NodeHandle &nh, const std::function< void(const ConfigType &)> config_callback=0, const std::function< void(const dynamic_reconfigure::ConfigDescription &)> description_callback=0) | |
| Client Constructs a statefull dynamic_reconfigure client. More... | |
| Client (const std::string &name, const std::function< void(const ConfigType &)> config_callback=0, const std::function< void(const dynamic_reconfigure::ConfigDescription &)> description_callback=0) | |
| Client Constructs a statefull dynamic_reconfigure client. More... | |
| bool | getCurrentConfiguration (ConfigType &configuration, const ros::Duration &timeout=ros::Duration(0)) |
| getCurrentConfiguration Gets the latest configuration from the dynamic_reconfigure::Server More... | |
| bool | getDefaultConfiguration (ConfigType &configuration, const ros::Duration &timeout=ros::Duration(0)) |
| getDefaultConfiguration Gets the latest default configuration from the dynamic_reconfigure::Server More... | |
| bool | getMaxConfiguration (ConfigType &configuration, const ros::Duration &timeout=ros::Duration(0)) |
| getMaxConfiguration Gets the latest maximum configuration from the dynamic_reconfigure::Server More... | |
| bool | getMinConfiguration (ConfigType &configuration, const ros::Duration &timeout=ros::Duration(0)) |
| getMinConfiguration Gets the latest minimum configuration from the dynamic_reconfigure::Server More... | |
| std::string | getName () const |
| getName Gets the name of the Dynamic Reconfigure Client More... | |
| bool | setConfiguration (ConfigType &configuration) |
| setConfiguration Attempts to set the configuration to the server More... | |
| bool | setConfiguration (const ConfigType &configuration) |
| setConfiguration Attempts to set the configuration to the server More... | |
| void | setConfigurationCallback (const std::function< void(const ConfigType &)> &config_callback) |
| setConfigurationCallback Sets the user defined configuration callback function More... | |
| void | setDescriptionCallback (const std::function< void(const dynamic_reconfigure::ConfigDescription &)> &description_callback) |
| setDescriptionCallback Sets the user defined description callback function More... | |
Private Member Functions | |
| void | configurationCallback (const dynamic_reconfigure::Config &configuration) |
| void | descriptionCallback (const dynamic_reconfigure::ConfigDescription &description) |
| bool | getDescription (ConfigDescription &configuration, const ros::Duration &timeout) |
Private Attributes | |
| std::function< void(const ConfigType &)> | config_callback_ |
| ros::Subscriber | config_sub_ |
| std::condition_variable | cv_ |
| ros::Subscriber | descr_sub_ |
| std::function< void(const dynamic_reconfigure::ConfigDescription &)> | description_callback_ |
| ConfigType | latest_configuration_ |
| dynamic_reconfigure::ConfigDescription | latest_description_ |
| std::mutex | mutex_ |
| std::string | name_ |
| ros::NodeHandle | nh_ |
| bool | received_configuration_ |
| bool | received_description_ |
| ros::ServiceClient | set_service_ |
|
inline |
Client Constructs a statefull dynamic_reconfigure client.
| name | The full path of the dynamic_reconfigure::Server |
| config_callback | A callback that should be called when the server informs the clients of a successful reconfiguration |
| description_callback | A callback that should be called when the server infrorms the clients of the description of the reconfiguration parameters and groups |
|
inline |
Client Constructs a statefull dynamic_reconfigure client.
| name | The full path of the dynamic_reconfigure::Server |
| nh | The nodehandle to the full path of the Server (for nodelets) |
| config_callback | A callback that should be called when the server informs the clients of a successful reconfiguration |
| description_callback | A callback that should be called when the server infrorms the clients of the description of the reconfiguration parameters and groups |
|
inlineprivate |
|
inlineprivate |
|
inline |
getCurrentConfiguration Gets the latest configuration from the dynamic_reconfigure::Server
| configuration | The object where the configuration will be stored |
| timeout | The duration that the client should wait for the configuration, if set to ros::Duration(0) will wait indefinetely |
|
inline |
getDefaultConfiguration Gets the latest default configuration from the dynamic_reconfigure::Server
| configuration | The object where the configuration will be stored |
| timeout | The duration that the client should wait for the configuration, if set to ros::Duration(0) will wait indefinetely |
|
inlineprivate |
|
inline |
getMaxConfiguration Gets the latest maximum configuration from the dynamic_reconfigure::Server
| configuration | The object where the configuration will be stored |
| timeout | The duration that the client should wait for the configuration, if set to ros::Duration(0) will wait indefinetely |
|
inline |
getMinConfiguration Gets the latest minimum configuration from the dynamic_reconfigure::Server
| configuration | The object where the configuration will be stored |
| timeout | The duration that the client should wait for the configuration, if set to ros::Duration(0) will wait indefinetely |
|
inline |
getName Gets the name of the Dynamic Reconfigure Client
|
inline |
|
inline |
|
inline |
|
inline |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |
|
private |