$search
#include <reconfigureable_node.h>
Protected Member Functions | |
Reconfigurable_Node (const std::string &ns) | |
void | setReconfigureCallback (const boost::function< void(T &, uint32_t level)> &callback) |
void | setReconfigureCallback2 (const boost::function< void(T &, uint32_t level)> &callback_s, const boost::function< void(T &)> &callback_get) |
void | updateConfig (const T &config_) |
Static Protected Member Functions | |
static void | callback_set (Reconfigurable_Node< T > *inst, T &config, uint32_t level) |
Protected Attributes | |
ros::ServiceServer | set_service_ |
Private Member Functions | |
std::string | getCorrectedNS (const std::string &s) |
Private Attributes | |
ros::NodeHandle | _n |
boost::function< void(T &)> | callback_get_ |
boost::function< void(T &, uint32_t level)> | callback_set_ |
bool | first_ |
dynamic_reconfigure::Server< T > | srv |
ros::Publisher | update_pub_ |
Definition at line 8 of file reconfigureable_node.h.
Reconfigurable_Node< T >::Reconfigurable_Node | ( | const std::string & | ns | ) | [inline, protected] |
Definition at line 11 of file reconfigureable_node.h.
static void Reconfigurable_Node< T >::callback_set | ( | Reconfigurable_Node< T > * | inst, | |
T & | config, | |||
uint32_t | level | |||
) | [inline, static, protected] |
Definition at line 36 of file reconfigureable_node.h.
std::string Reconfigurable_Node< T >::getCorrectedNS | ( | const std::string & | s | ) | [inline, private] |
Definition at line 55 of file reconfigureable_node.h.
void Reconfigurable_Node< T >::setReconfigureCallback | ( | const boost::function< void(T &, uint32_t level)> & | callback | ) | [inline, protected] |
Definition at line 16 of file reconfigureable_node.h.
void Reconfigurable_Node< T >::setReconfigureCallback2 | ( | const boost::function< void(T &, uint32_t level)> & | callback_s, | |
const boost::function< void(T &)> & | callback_get | |||
) | [inline, protected] |
Definition at line 20 of file reconfigureable_node.h.
void Reconfigurable_Node< T >::updateConfig | ( | const T & | config_ | ) | [inline, protected] |
Definition at line 27 of file reconfigureable_node.h.
ros::NodeHandle Reconfigurable_Node< T >::_n [private] |
Definition at line 48 of file reconfigureable_node.h.
boost::function<void(T &)> Reconfigurable_Node< T >::callback_get_ [private] |
Definition at line 53 of file reconfigureable_node.h.
boost::function<void(T &, uint32_t level)> Reconfigurable_Node< T >::callback_set_ [private] |
Definition at line 52 of file reconfigureable_node.h.
bool Reconfigurable_Node< T >::first_ [private] |
Definition at line 51 of file reconfigureable_node.h.
ros::ServiceServer Reconfigurable_Node< T >::set_service_ [protected] |
Definition at line 10 of file reconfigureable_node.h.
dynamic_reconfigure::Server<T> Reconfigurable_Node< T >::srv [private] |
Definition at line 49 of file reconfigureable_node.h.
ros::Publisher Reconfigurable_Node< T >::update_pub_ [private] |
Definition at line 50 of file reconfigureable_node.h.