Classes | Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Private Types | Static Private Member Functions | Static Private Attributes | List of all members
rtt_dynamic_reconfigure::AutoConfig Class Reference

#include <auto_config.h>

Inheritance diagram for rtt_dynamic_reconfigure::AutoConfig:
Inheritance graph
[legend]

Classes

struct  Cache
 

Public Types

typedef Server< AutoConfigServerType
 
- Public Types inherited from RTT::PropertyBag
typedef Properties::const_iterator const_iterator
 
typedef Properties::iterator iterator
 
typedef std::vector< std::string > Names
 
typedef std::vector< base::PropertyBase * > Properties
 
typedef Properties PropertyContainerType
 

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 ()
 
- Public Member Functions inherited from RTT::PropertyBag
void add (base::PropertyBase *p)
 
Property< T > & addProperty (const std::string &name, T &attr)
 
bool addProperty (base::PropertyBase &p)
 
iterator begin ()
 
const_iterator begin () const
 
void clear ()
 
bool empty () const
 
iterator end ()
 
const_iterator end () const
 
base::PropertyBasefind (const std::string &name) const
 
base::PropertyBasefindValue (const T &value) const
 
base::PropertyBasegetItem (int i) const
 
PropertiesgetProperties ()
 
const PropertiesgetProperties () const
 
Properties getProperties (const std::string &name) const
 
base::PropertyBasegetProperty (const std::string &name) const
 
Names getPropertyNames () const
 
Property< T > * getPropertyType (const std::string &name) const
 
const std::string & getType () const
 
void identify (base::PropertyIntrospection *pi) const
 
void identify (base::PropertyBagVisitor *pi) const
 
void list (Names &names) const
 
Names list () const
 
PropertyBagoperator<< (base::PropertyBase *item)
 
PropertyBagoperator<<= (const PropertyBag &source)
 
PropertyBagoperator= (const PropertyBag &orig)
 
bool ownProperty (base::PropertyBase *p)
 
bool ownsProperty (base::PropertyBase *p) const
 
 PropertyBag (const std::string &_type)
 
 PropertyBag ()
 
 PropertyBag (const PropertyBag &orig)
 
void remove (base::PropertyBase *p)
 
bool removeProperty (base::PropertyBase *p)
 
void setType (const std::string &newtype)
 
size_t size () const
 
 ~PropertyBag ()
 

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< CacheCachePtr
 

Static Private Member Functions

static void buildCache (const ServerType *server, RTT::TaskContext *owner)
 

Static Private Attributes

static std::map< const ServerType *, CachePtrcache_
 
static boost::shared_mutex cache_mutex_
 

Additional Inherited Members

- Protected Attributes inherited from RTT::PropertyBag
Properties mowned_props
 
Properties mproperties
 
std::string type
 

Detailed Description

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 41 of file auto_config.h.

Member Typedef Documentation

Definition at line 78 of file auto_config.h.

Definition at line 44 of file auto_config.h.

Constructor & Destructor Documentation

rtt_dynamic_reconfigure::AutoConfig::AutoConfig ( )

Definition at line 99 of file auto_config.cpp.

rtt_dynamic_reconfigure::AutoConfig::AutoConfig ( const RTT::PropertyBag bag)

Definition at line 104 of file auto_config.cpp.

rtt_dynamic_reconfigure::AutoConfig::~AutoConfig ( )

Definition at line 110 of file auto_config.cpp.

Member Function Documentation

void rtt_dynamic_reconfigure::AutoConfig::__clamp__ ( const ServerType server)

Definition at line 335 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 330 of file auto_config.cpp.

const AutoConfig & rtt_dynamic_reconfigure::AutoConfig::__getDefault__ ( const ServerType server)
static

Definition at line 518 of file auto_config.cpp.

dynamic_reconfigure::ConfigDescriptionPtr rtt_dynamic_reconfigure::AutoConfig::__getDescriptionMessage__ ( const ServerType server)
static

Definition at line 511 of file auto_config.cpp.

const AutoConfig & rtt_dynamic_reconfigure::AutoConfig::__getMax__ ( const ServerType server)
static

Definition at line 525 of file auto_config.cpp.

const AutoConfig & rtt_dynamic_reconfigure::AutoConfig::__getMin__ ( const ServerType server)
static

Definition at line 532 of file auto_config.cpp.

uint32_t rtt_dynamic_reconfigure::AutoConfig::__level__ ( const AutoConfig config) const

Definition at line 343 of file auto_config.cpp.

void rtt_dynamic_reconfigure::AutoConfig::__refreshDescription__ ( const ServerType server)
static

Definition at line 539 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 325 of file auto_config.cpp.

void rtt_dynamic_reconfigure::AutoConfig::buildCache ( const ServerType server,
RTT::TaskContext owner 
)
staticprivate

Definition at line 491 of file auto_config.cpp.

bool rtt_dynamic_reconfigure::AutoConfig::fromProperties ( const RTT::PropertyBag source)

Definition at line 355 of file auto_config.cpp.

bool rtt_dynamic_reconfigure::AutoConfig::updateProperties ( RTT::PropertyBag target) const

Definition at line 348 of file auto_config.cpp.

Member Data Documentation

std::map< const AutoConfig::ServerType *, AutoConfig::CachePtr > rtt_dynamic_reconfigure::AutoConfig::cache_
staticprivate

Definition at line 80 of file auto_config.h.

boost::shared_mutex rtt_dynamic_reconfigure::AutoConfig::cache_mutex_
staticprivate

Definition at line 81 of file auto_config.h.

int rtt_dynamic_reconfigure::AutoConfig::id

Definition at line 50 of file auto_config.h.

std::string rtt_dynamic_reconfigure::AutoConfig::name

Definition at line 47 of file auto_config.h.

int rtt_dynamic_reconfigure::AutoConfig::parent

Definition at line 49 of file auto_config.h.

std::string rtt_dynamic_reconfigure::AutoConfig::prefix_

Definition at line 46 of file auto_config.h.

bool rtt_dynamic_reconfigure::AutoConfig::state

Definition at line 51 of file auto_config.h.

std::string rtt_dynamic_reconfigure::AutoConfig::type

Definition at line 48 of file auto_config.h.


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


rtt_dynamic_reconfigure
Author(s): Johannes Meyer
autogenerated on Mon May 10 2021 02:44:57