#include <server.h>
Public Member Functions | |
void | advertise (std::string ns=std::string()) |
const ConfigType & | getConfig () const |
void | getConfigDefault (ConfigType &config) const |
const ConfigType & | getConfigDefault () const |
ConfigType & | getConfigDefault () |
void | getConfigMax (ConfigType &max) const |
const ConfigType & | getConfigMax () const |
ConfigType & | getConfigMax () |
void | getConfigMin (ConfigType &min) const |
const ConfigType & | getConfigMin () const |
ConfigType & | getConfigMin () |
dynamic_reconfigure::ConfigDescriptionPtr | getDescriptionMessage () |
void | refresh () |
Server (const std::string &name, RTT::TaskContext *owner) | |
Server (RTT::TaskContext *owner) | |
void | setConfigDefault (const ConfigType &config) |
void | setConfigMax (const ConfigType &config) |
void | setConfigMin (const ConfigType &config) |
void | setNotificationCallback (RTT::OperationInterfacePart *impl) |
void | setUpdateCallback (RTT::OperationInterfacePart *impl) |
void | setUpdater (UpdaterType *updater) |
void | shutdown () |
void | updateConfig (const ConfigType &config) |
bool | updated () |
UpdaterType * | updater () const |
virtual | ~Server () |
Private Types | |
typedef boost::shared_ptr < Server< ConfigType > > | shared_ptr |
typedef dynamic_reconfigure_traits < ConfigType > | traits |
typedef Updater< ConfigType > | UpdaterType |
Private Member Functions | |
void | construct () |
void | PublishDescription () |
bool | setConfigCallback (dynamic_reconfigure::Reconfigure::Request &req, dynamic_reconfigure::Reconfigure::Response &rsp) |
void | updateConfigInternal (const ConfigType &config) |
bool | updatePropertiesDefaultImpl (const RTT::PropertyBag &bag, uint32_t) |
Private Attributes | |
ConfigType | config_ |
ConfigType | default_ |
ros::Publisher | descr_pub_ |
bool | initialized_ |
ConfigType | max_ |
ConfigType | min_ |
RTT::os::MutexRecursive | mutex_ |
ros::NodeHandle * | node_handle_ |
RTT::OperationCaller < NotifyCallbackSignature > | notify_callback_ |
ros::ServiceServer | set_service_ |
RTT::OperationCaller < UpdateCallbackSignature > | update_callback_ |
RTT::OperationCaller < UpdateCallbackConstSignature > | update_callback_const_ |
RTT::Operation < UpdateCallbackConstSignature > | update_callback_default_impl_ |
ros::Publisher | update_pub_ |
boost::shared_ptr< UpdaterType > | updater_ |
Friends | |
class | DynamicReconfigureTestComponent |
The Server<ConfigType> class implements a dynamic_reconfigure server as an RTT service. It provides a similar API than the pure cpp dynamic_reconfigure server implemented in the dynamic_reconfigure package.
typedef boost::shared_ptr< Server<ConfigType> > rtt_dynamic_reconfigure::Server< ConfigType >::shared_ptr [private] |
Reimplemented from RTT::Service.
typedef dynamic_reconfigure_traits<ConfigType> rtt_dynamic_reconfigure::Server< ConfigType >::traits [private] |
typedef Updater<ConfigType> rtt_dynamic_reconfigure::Server< ConfigType >::UpdaterType [private] |
rtt_dynamic_reconfigure::Server< ConfigType >::Server | ( | const std::string & | name, |
RTT::TaskContext * | owner | ||
) | [inline] |
Construct a named rtt_dynamic_reconfigure server.
name | name of the service instance |
owner | pointer to the TaskContext instance owning this service/to be configured |
rtt_dynamic_reconfigure::Server< ConfigType >::Server | ( | RTT::TaskContext * | owner | ) | [inline] |
Construct an rtt_dynamic_reconfigure server named "reconfigure".
owner | pointer to the TaskContext instance owning this service/to be configured |
virtual rtt_dynamic_reconfigure::Server< ConfigType >::~Server | ( | ) | [inline, virtual] |
Destruct the rtt_dynamic_reconfigure server. This unadvertises the dynamic_reconfigure topics and services.
void rtt_dynamic_reconfigure::Server< ConfigType >::advertise | ( | std::string | ns = std::string() | ) | [inline] |
Advertise the dynamic_reconfigure topics and services at the master. Needs to be called explicitly after construction, e.g from the owner's configureHook().
ns | The ROS namespace this dynamic_reconfigure server should be advertised in. If empty, defaults to the name of the owning TaskContext. |
void rtt_dynamic_reconfigure::Server< ConfigType >::construct | ( | ) | [inline, private] |
const ConfigType& rtt_dynamic_reconfigure::Server< ConfigType >::getConfig | ( | ) | const [inline] |
void rtt_dynamic_reconfigure::Server< ConfigType >::getConfigDefault | ( | ConfigType & | config | ) | const [inline] |
const ConfigType& rtt_dynamic_reconfigure::Server< ConfigType >::getConfigDefault | ( | ) | const [inline] |
ConfigType& rtt_dynamic_reconfigure::Server< ConfigType >::getConfigDefault | ( | ) | [inline] |
void rtt_dynamic_reconfigure::Server< ConfigType >::getConfigMax | ( | ConfigType & | max | ) | const [inline] |
const ConfigType& rtt_dynamic_reconfigure::Server< ConfigType >::getConfigMax | ( | ) | const [inline] |
ConfigType& rtt_dynamic_reconfigure::Server< ConfigType >::getConfigMax | ( | ) | [inline] |
void rtt_dynamic_reconfigure::Server< ConfigType >::getConfigMin | ( | ConfigType & | min | ) | const [inline] |
const ConfigType& rtt_dynamic_reconfigure::Server< ConfigType >::getConfigMin | ( | ) | const [inline] |
ConfigType& rtt_dynamic_reconfigure::Server< ConfigType >::getConfigMin | ( | ) | [inline] |
dynamic_reconfigure::ConfigDescriptionPtr rtt_dynamic_reconfigure::Server< ConfigType >::getDescriptionMessage | ( | ) | [inline] |
void rtt_dynamic_reconfigure::Server< ConfigType >::PublishDescription | ( | ) | [inline, private] |
void rtt_dynamic_reconfigure::Server< ConfigType >::refresh | ( | ) | [inline] |
Refresh the config description, minimum and maximum values, get and publish the current config from the default values and the TaskContext's properties. Call this function whenever properties have been added or removed or the minimum, maximum or default values have been changed.
bool rtt_dynamic_reconfigure::Server< ConfigType >::setConfigCallback | ( | dynamic_reconfigure::Reconfigure::Request & | req, |
dynamic_reconfigure::Reconfigure::Response & | rsp | ||
) | [inline, private] |
void rtt_dynamic_reconfigure::Server< ConfigType >::setConfigDefault | ( | const ConfigType & | config | ) | [inline] |
void rtt_dynamic_reconfigure::Server< ConfigType >::setConfigMax | ( | const ConfigType & | config | ) | [inline] |
void rtt_dynamic_reconfigure::Server< ConfigType >::setConfigMin | ( | const ConfigType & | config | ) | [inline] |
void rtt_dynamic_reconfigure::Server< ConfigType >::setNotificationCallback | ( | RTT::OperationInterfacePart * | impl | ) | [inline] |
void rtt_dynamic_reconfigure::Server< ConfigType >::setUpdateCallback | ( | RTT::OperationInterfacePart * | impl | ) | [inline] |
Sets the property update callback (defaults to RTT::updateProperties(*(getOwner()->properties()), ...))
impl | an Operation with the signature bool(const RTT::PropertyBag &) |
void rtt_dynamic_reconfigure::Server< ConfigType >::setUpdater | ( | UpdaterType * | updater | ) | [inline] |
void rtt_dynamic_reconfigure::Server< ConfigType >::shutdown | ( | ) | [inline] |
Unadvertise the dynamic_reconfigure topics and services at the master. This is the contrary of the advertise() member function.
void rtt_dynamic_reconfigure::Server< ConfigType >::updateConfig | ( | const ConfigType & | config | ) | [inline] |
void rtt_dynamic_reconfigure::Server< ConfigType >::updateConfigInternal | ( | const ConfigType & | config | ) | [inline, private] |
bool rtt_dynamic_reconfigure::Server< ConfigType >::updated | ( | ) | [inline] |
bool rtt_dynamic_reconfigure::Server< ConfigType >::updatePropertiesDefaultImpl | ( | const RTT::PropertyBag & | bag, |
uint32_t | |||
) | [inline, private] |
UpdaterType* rtt_dynamic_reconfigure::Server< ConfigType >::updater | ( | ) | const [inline] |
Retrieve/construct the Updater instance of this rtt_dynamic_reconfigure server.
friend class DynamicReconfigureTestComponent [friend] |
ConfigType rtt_dynamic_reconfigure::Server< ConfigType >::config_ [private] |
ConfigType rtt_dynamic_reconfigure::Server< ConfigType >::default_ [private] |
ros::Publisher rtt_dynamic_reconfigure::Server< ConfigType >::descr_pub_ [private] |
bool rtt_dynamic_reconfigure::Server< ConfigType >::initialized_ [private] |
ConfigType rtt_dynamic_reconfigure::Server< ConfigType >::max_ [private] |
ConfigType rtt_dynamic_reconfigure::Server< ConfigType >::min_ [private] |
RTT::os::MutexRecursive rtt_dynamic_reconfigure::Server< ConfigType >::mutex_ [private] |
ros::NodeHandle* rtt_dynamic_reconfigure::Server< ConfigType >::node_handle_ [private] |
RTT::OperationCaller<NotifyCallbackSignature> rtt_dynamic_reconfigure::Server< ConfigType >::notify_callback_ [private] |
ros::ServiceServer rtt_dynamic_reconfigure::Server< ConfigType >::set_service_ [private] |
RTT::OperationCaller<UpdateCallbackSignature> rtt_dynamic_reconfigure::Server< ConfigType >::update_callback_ [private] |
RTT::OperationCaller<UpdateCallbackConstSignature> rtt_dynamic_reconfigure::Server< ConfigType >::update_callback_const_ [private] |
RTT::Operation<UpdateCallbackConstSignature> rtt_dynamic_reconfigure::Server< ConfigType >::update_callback_default_impl_ [private] |
ros::Publisher rtt_dynamic_reconfigure::Server< ConfigType >::update_pub_ [private] |
boost::shared_ptr<UpdaterType> rtt_dynamic_reconfigure::Server< ConfigType >::updater_ [mutable, private] |