Public Member Functions | Private Member Functions | Private Attributes | List of all members
dynamic_reconfigure::Client< ConfigType > Class Template Reference

#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_
 

Detailed Description

template<class ConfigType>
class dynamic_reconfigure::Client< ConfigType >

Definition at line 58 of file client.h.

Constructor & Destructor Documentation

◆ Client() [1/2]

template<class ConfigType >
dynamic_reconfigure::Client< ConfigType >::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 
)
inline

Client Constructs a statefull dynamic_reconfigure client.

Parameters
nameThe full path of the dynamic_reconfigure::Server
config_callbackA callback that should be called when the server informs the clients of a successful reconfiguration
description_callbackA callback that should be called when the server infrorms the clients of the description of the reconfiguration parameters and groups

Definition at line 69 of file client.h.

◆ Client() [2/2]

template<class ConfigType >
dynamic_reconfigure::Client< ConfigType >::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 
)
inline

Client Constructs a statefull dynamic_reconfigure client.

Parameters
nameThe full path of the dynamic_reconfigure::Server
nhThe nodehandle to the full path of the Server (for nodelets)
config_callbackA callback that should be called when the server informs the clients of a successful reconfiguration
description_callbackA callback that should be called when the server infrorms the clients of the description of the reconfiguration parameters and groups

Definition at line 100 of file client.h.

Member Function Documentation

◆ configurationCallback()

template<class ConfigType >
void dynamic_reconfigure::Client< ConfigType >::configurationCallback ( const dynamic_reconfigure::Config configuration)
inlineprivate

Definition at line 259 of file client.h.

◆ descriptionCallback()

template<class ConfigType >
void dynamic_reconfigure::Client< ConfigType >::descriptionCallback ( const dynamic_reconfigure::ConfigDescription description)
inlineprivate

Definition at line 281 of file client.h.

◆ getCurrentConfiguration()

template<class ConfigType >
bool dynamic_reconfigure::Client< ConfigType >::getCurrentConfiguration ( ConfigType &  configuration,
const ros::Duration timeout = ros::Duration(0) 
)
inline

getCurrentConfiguration Gets the latest configuration from the dynamic_reconfigure::Server

Parameters
configurationThe object where the configuration will be stored
timeoutThe duration that the client should wait for the configuration, if set to ros::Duration(0) will wait indefinetely
Returns
False if the timeout has happened

Definition at line 174 of file client.h.

◆ getDefaultConfiguration()

template<class ConfigType >
bool dynamic_reconfigure::Client< ConfigType >::getDefaultConfiguration ( ConfigType &  configuration,
const ros::Duration timeout = ros::Duration(0) 
)
inline

getDefaultConfiguration Gets the latest default configuration from the dynamic_reconfigure::Server

Parameters
configurationThe object where the configuration will be stored
timeoutThe duration that the client should wait for the configuration, if set to ros::Duration(0) will wait indefinetely
Returns
False if the timeout has happened

Definition at line 205 of file client.h.

◆ getDescription()

template<class ConfigType >
bool dynamic_reconfigure::Client< ConfigType >::getDescription ( ConfigDescription configuration,
const ros::Duration timeout 
)
inlineprivate

Definition at line 303 of file client.h.

◆ getMaxConfiguration()

template<class ConfigType >
bool dynamic_reconfigure::Client< ConfigType >::getMaxConfiguration ( ConfigType &  configuration,
const ros::Duration timeout = ros::Duration(0) 
)
inline

getMaxConfiguration Gets the latest maximum configuration from the dynamic_reconfigure::Server

Parameters
configurationThe object where the configuration will be stored
timeoutThe duration that the client should wait for the configuration, if set to ros::Duration(0) will wait indefinetely
Returns
False if the timeout has happened

Definition at line 242 of file client.h.

◆ getMinConfiguration()

template<class ConfigType >
bool dynamic_reconfigure::Client< ConfigType >::getMinConfiguration ( ConfigType &  configuration,
const ros::Duration timeout = ros::Duration(0) 
)
inline

getMinConfiguration Gets the latest minimum configuration from the dynamic_reconfigure::Server

Parameters
configurationThe object where the configuration will be stored
timeoutThe duration that the client should wait for the configuration, if set to ros::Duration(0) will wait indefinetely
Returns
False if the timeout has happened

Definition at line 224 of file client.h.

◆ getName()

template<class ConfigType >
std::string dynamic_reconfigure::Client< ConfigType >::getName ( ) const
inline

getName Gets the name of the Dynamic Reconfigure Client

Returns
Copy of the member variable

Definition at line 256 of file client.h.

◆ setConfiguration() [1/2]

template<class ConfigType >
bool dynamic_reconfigure::Client< ConfigType >::setConfiguration ( ConfigType &  configuration)
inline

setConfiguration Attempts to set the configuration to the server

Parameters
configurationThe requested configuration, gets overwritten with the reply from the reconfigure server
Returns
True if the server accepted the request (not the reconfiguration)

Definition at line 154 of file client.h.

◆ setConfiguration() [2/2]

template<class ConfigType >
bool dynamic_reconfigure::Client< ConfigType >::setConfiguration ( const ConfigType &  configuration)
inline

setConfiguration Attempts to set the configuration to the server

Parameters
configurationThe requested configuration
Returns
True if the server accepted the request (not the reconfiguration)

Definition at line 144 of file client.h.

◆ setConfigurationCallback()

template<class ConfigType >
void dynamic_reconfigure::Client< ConfigType >::setConfigurationCallback ( const std::function< void(const ConfigType &)> &  config_callback)
inline

setConfigurationCallback Sets the user defined configuration callback function

Parameters
config_callbackA function pointer

Definition at line 126 of file client.h.

◆ setDescriptionCallback()

template<class ConfigType >
void dynamic_reconfigure::Client< ConfigType >::setDescriptionCallback ( const std::function< void(const dynamic_reconfigure::ConfigDescription &)> &  description_callback)
inline

setDescriptionCallback Sets the user defined description callback function

Parameters
description_callbackA function pointer

Definition at line 135 of file client.h.

Member Data Documentation

◆ config_callback_

template<class ConfigType >
std::function<void(const ConfigType&)> dynamic_reconfigure::Client< ConfigType >::config_callback_
private

Definition at line 338 of file client.h.

◆ config_sub_

template<class ConfigType >
ros::Subscriber dynamic_reconfigure::Client< ConfigType >::config_sub_
private

Definition at line 336 of file client.h.

◆ cv_

template<class ConfigType >
std::condition_variable dynamic_reconfigure::Client< ConfigType >::cv_
private

Definition at line 331 of file client.h.

◆ descr_sub_

template<class ConfigType >
ros::Subscriber dynamic_reconfigure::Client< ConfigType >::descr_sub_
private

Definition at line 335 of file client.h.

◆ description_callback_

template<class ConfigType >
std::function<void(const dynamic_reconfigure::ConfigDescription&)> dynamic_reconfigure::Client< ConfigType >::description_callback_
private

Definition at line 340 of file client.h.

◆ latest_configuration_

template<class ConfigType >
ConfigType dynamic_reconfigure::Client< ConfigType >::latest_configuration_
private

Definition at line 328 of file client.h.

◆ latest_description_

template<class ConfigType >
dynamic_reconfigure::ConfigDescription dynamic_reconfigure::Client< ConfigType >::latest_description_
private

Definition at line 330 of file client.h.

◆ mutex_

template<class ConfigType >
std::mutex dynamic_reconfigure::Client< ConfigType >::mutex_
private

Definition at line 332 of file client.h.

◆ name_

template<class ConfigType >
std::string dynamic_reconfigure::Client< ConfigType >::name_
private

Definition at line 326 of file client.h.

◆ nh_

template<class ConfigType >
ros::NodeHandle dynamic_reconfigure::Client< ConfigType >::nh_
private

Definition at line 333 of file client.h.

◆ received_configuration_

template<class ConfigType >
bool dynamic_reconfigure::Client< ConfigType >::received_configuration_
private

Definition at line 327 of file client.h.

◆ received_description_

template<class ConfigType >
bool dynamic_reconfigure::Client< ConfigType >::received_description_
private

Definition at line 329 of file client.h.

◆ set_service_

template<class ConfigType >
ros::ServiceClient dynamic_reconfigure::Client< ConfigType >::set_service_
private

Definition at line 334 of file client.h.


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


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:15