#include <auto_config.h>

Classes | |
| struct | Cache |
Public Types | |
| typedef Server< AutoConfig > | ServerType |
Public Member Functions | |
| void | __clamp__ (const ServerType *server) |
| bool | __fromMessage__ (dynamic_reconfigure::Config &msg, const AutoConfig &sample) |
| void | __fromServer__ (const ros::NodeHandle &nh) |
| uint32_t | __level__ (const AutoConfig &config) const |
| void | __toMessage__ (dynamic_reconfigure::Config &msg) const |
| void | __toServer__ (const ros::NodeHandle &nh) const |
| AutoConfig () | |
| AutoConfig (const RTT::PropertyBag &bag) | |
| bool | fromProperties (const RTT::PropertyBag &) |
| bool | updateProperties (RTT::PropertyBag &) const |
| ~AutoConfig () | |
Static Public Member Functions | |
| static bool | __fromMessage__ (AutoConfig &config, dynamic_reconfigure::Config &msg, const AutoConfig &sample) |
| static const AutoConfig & | __getDefault__ (const ServerType *server) |
| static dynamic_reconfigure::ConfigDescriptionPtr | __getDescriptionMessage__ (const ServerType *server) |
| static const AutoConfig & | __getMax__ (const ServerType *server) |
| static const AutoConfig & | __getMin__ (const ServerType *server) |
| static void | __refreshDescription__ (const ServerType *server) |
| static void | __toMessage__ (const AutoConfig &config, dynamic_reconfigure::Config &msg) |
Public Attributes | |
| int | id |
| std::string | name |
| int | parent |
| std::string | prefix_ |
| bool | state |
| std::string | type |
Private Types | |
| typedef boost::shared_ptr< Cache > | CachePtr |
Static Private Member Functions | |
| static void | buildCache (const ServerType *server, RTT::TaskContext *owner) |
Static Private Attributes | |
| static std::map< const ServerType *, CachePtr > | cache_ |
| static boost::shared_mutex | cache_mutex_ |
The AutoConfig class serves as a generic config type for rtt_dynamic_reconfigure::Server that dynamically creates the Config and ConfigDescription from the owner TaskContext's properties.
Definition at line 46 of file auto_config.h.
typedef boost::shared_ptr<Cache> rtt_dynamic_reconfigure::AutoConfig::CachePtr [private] |
Definition at line 83 of file auto_config.h.
Definition at line 49 of file auto_config.h.
Definition at line 104 of file auto_config.cpp.
| rtt_dynamic_reconfigure::AutoConfig::AutoConfig | ( | const RTT::PropertyBag & | bag | ) |
Definition at line 109 of file auto_config.cpp.
Definition at line 115 of file auto_config.cpp.
| void rtt_dynamic_reconfigure::AutoConfig::__clamp__ | ( | const ServerType * | server | ) |
Definition at line 340 of file auto_config.cpp.
| bool rtt_dynamic_reconfigure::AutoConfig::__fromMessage__ | ( | dynamic_reconfigure::Config & | msg, |
| const AutoConfig & | sample | ||
| ) |
| static bool rtt_dynamic_reconfigure::AutoConfig::__fromMessage__ | ( | AutoConfig & | config, |
| dynamic_reconfigure::Config & | msg, | ||
| const AutoConfig & | sample | ||
| ) | [static] |
| void rtt_dynamic_reconfigure::AutoConfig::__fromServer__ | ( | const ros::NodeHandle & | nh | ) |
Definition at line 335 of file auto_config.cpp.
| const AutoConfig & rtt_dynamic_reconfigure::AutoConfig::__getDefault__ | ( | const ServerType * | server | ) | [static] |
Definition at line 523 of file auto_config.cpp.
| dynamic_reconfigure::ConfigDescriptionPtr rtt_dynamic_reconfigure::AutoConfig::__getDescriptionMessage__ | ( | const ServerType * | server | ) | [static] |
Definition at line 516 of file auto_config.cpp.
| const AutoConfig & rtt_dynamic_reconfigure::AutoConfig::__getMax__ | ( | const ServerType * | server | ) | [static] |
Definition at line 530 of file auto_config.cpp.
| const AutoConfig & rtt_dynamic_reconfigure::AutoConfig::__getMin__ | ( | const ServerType * | server | ) | [static] |
Definition at line 537 of file auto_config.cpp.
| uint32_t rtt_dynamic_reconfigure::AutoConfig::__level__ | ( | const AutoConfig & | config | ) | const |
Definition at line 348 of file auto_config.cpp.
| void rtt_dynamic_reconfigure::AutoConfig::__refreshDescription__ | ( | const ServerType * | server | ) | [static] |
Definition at line 544 of file auto_config.cpp.
| void rtt_dynamic_reconfigure::AutoConfig::__toMessage__ | ( | dynamic_reconfigure::Config & | msg | ) | const |
| static void rtt_dynamic_reconfigure::AutoConfig::__toMessage__ | ( | const AutoConfig & | config, |
| dynamic_reconfigure::Config & | msg | ||
| ) | [static] |
| void rtt_dynamic_reconfigure::AutoConfig::__toServer__ | ( | const ros::NodeHandle & | nh | ) | const |
Definition at line 330 of file auto_config.cpp.
| void rtt_dynamic_reconfigure::AutoConfig::buildCache | ( | const ServerType * | server, |
| RTT::TaskContext * | owner | ||
| ) | [static, private] |
Definition at line 496 of file auto_config.cpp.
| bool rtt_dynamic_reconfigure::AutoConfig::fromProperties | ( | const RTT::PropertyBag & | source | ) |
Definition at line 360 of file auto_config.cpp.
| bool rtt_dynamic_reconfigure::AutoConfig::updateProperties | ( | RTT::PropertyBag & | target | ) | const |
Definition at line 353 of file auto_config.cpp.
std::map< const AutoConfig::ServerType *, AutoConfig::CachePtr > rtt_dynamic_reconfigure::AutoConfig::cache_ [static, private] |
Definition at line 85 of file auto_config.h.
boost::shared_mutex rtt_dynamic_reconfigure::AutoConfig::cache_mutex_ [static, private] |
Definition at line 86 of file auto_config.h.
Definition at line 55 of file auto_config.h.
| std::string rtt_dynamic_reconfigure::AutoConfig::name |
Definition at line 52 of file auto_config.h.
Definition at line 54 of file auto_config.h.
| std::string rtt_dynamic_reconfigure::AutoConfig::prefix_ |
Definition at line 51 of file auto_config.h.
Definition at line 56 of file auto_config.h.
| std::string rtt_dynamic_reconfigure::AutoConfig::type |
Reimplemented from RTT::PropertyBag.
Definition at line 53 of file auto_config.h.