server.h
Go to the documentation of this file.
1 /*
2  * (C) 2009-2010, Willow Garage, Inc
3  * (C) 2014, Intermodalics BVBA
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * 2. Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * 3. Neither the name of the copyright holder nor the names of its contributors
14  * may be used to endorse or promote products derived from this software
15  * without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
18  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
19  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
20  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
21  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
22  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
23  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
24  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
26  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
27  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28  * POSSIBILITY OF SUCH DAMAGE.
29  */
30 
31 #ifndef RTT_DYNAMIC_RECONFIGURE_SERVER_H
32 #define RTT_DYNAMIC_RECONFIGURE_SERVER_H
33 
34 #include <rtt/Service.hpp>
35 #include <rtt/TaskContext.hpp>
36 #include <rtt/os/Mutex.hpp>
37 #include <rtt/Logger.hpp>
38 #include <rtt/Operation.hpp>
39 #include <rtt/OperationCaller.hpp>
40 
43 
44 #include <ros/ros.h>
45 
46 #include <dynamic_reconfigure/Reconfigure.h>
47 #include <dynamic_reconfigure/Config.h>
48 #include <dynamic_reconfigure/ConfigDescription.h>
49 
50 #include <rtt/rtt-config.h>
51 #if !defined(RTT_VERSION_GTE)
52  #define RTT_VERSION_GTE(major,minor,patch) \
53  ((RTT_VERSION_MAJOR > major) || (RTT_VERSION_MAJOR == major && \
54  (RTT_VERSION_MINOR > minor) || (RTT_VERSION_MINOR == minor && \
55  (RTT_VERSION_PATCH >= patch))))
56 #endif
57 
58 namespace rtt_dynamic_reconfigure {
59 
60 template <class ConfigType> class Server;
61 typedef bool (UpdateCallbackSignature)(RTT::PropertyBag &bag, uint32_t level);
62 typedef bool (UpdateCallbackConstSignature)(const RTT::PropertyBag &bag, uint32_t level);
63 typedef void (NotifyCallbackSignature)(uint32_t level);
64 
70 template <class ConfigType>
71 struct Updater {
72  virtual bool propertiesFromConfig(ConfigType &, uint32_t, RTT::PropertyBag &) { return false; }
73  virtual bool configFromProperties(ConfigType &, const RTT::PropertyBag &) { return false; }
74 };
75 
76 template <class ConfigType>
79 
86  static void getMin(ConfigType &min, const ServerType *) { min = ConfigType::__getMin__(); }
87 
94  static void getMax(ConfigType &max, const ServerType *) { max = ConfigType::__getMax__(); }
95 
102  static void getDefault(ConfigType &dflt, const ServerType *) { dflt = ConfigType::__getDefault__(); }
103 
110  static dynamic_reconfigure::ConfigDescriptionPtr getDescriptionMessage(const ServerType *) { return dynamic_reconfigure::ConfigDescriptionPtr(new dynamic_reconfigure::ConfigDescription(ConfigType::__getDescriptionMessage__())); }
111 
115  static const bool canRefresh = false;
116 
122  static void refreshDescription(const ServerType *) {}
123 
131  static void toMessage(ConfigType &config, dynamic_reconfigure::Config &message, const ServerType *) { config.__toMessage__(message); }
132 
140  static void fromMessage(ConfigType &config, dynamic_reconfigure::Config &message, const ServerType *) { config.__fromMessage__(message); }
141 
148  static void clamp(ConfigType &config, const ServerType *) { config.__clamp__(); }
149 
156  static RTT::internal::AssignableDataSource<RTT::PropertyBag>::shared_ptr getDataSource(ConfigType &config, const ServerType *server) {
158  if (!server->updater()->propertiesFromConfig(config, ~0, ds->set()))
159  ds.reset();
160  return ds;
161  }
162 };
163 
164 namespace {
165  struct null_deleter {
166  void operator()(const void *) const {}
167  };
168 }
169 
170 // Forward declaration of class DynamicReconfigureTestComponent
171 class DynamicReconfigureTestComponent;
172 
177 template <class ConfigType>
178 class Server : public RTT::Service
179 {
180 private:
184 
190 
191  ConfigType config_;
192  ConfigType min_;
193  ConfigType max_;
194  ConfigType default_;
195 
198 
203 
204 public:
211  Server(const std::string &name, RTT::TaskContext *owner)
212  : RTT::Service(name, owner)
213  , node_handle_(0)
214  , update_callback_default_impl_("updateProperties", &Server<ConfigType>::updatePropertiesDefaultImpl, this, RTT::OwnThread, owner->engine())
215  {
216  construct();
217  }
218 
225  : RTT::Service("reconfigure", owner)
226  , node_handle_(0)
227  , update_callback_default_impl_("updateProperties", &Server<ConfigType>::updatePropertiesDefaultImpl, this, RTT::OwnThread, owner->engine())
228  {
229  construct();
230  }
231 
236  virtual ~Server() {
237  shutdown();
238  }
239 
245  const ConfigType &getConfig() const { return config_; }
246 
252  void updateConfig(const ConfigType &config)
253  {
254  updateConfigInternal(config);
255  }
256 
262  void getConfigMax(ConfigType &max) const
263  {
264  max = max_;
265  }
266 
272  const ConfigType &getConfigMax() const { return max_; }
273 
279  ConfigType &getConfigMax() { return max_; }
280 
286  void getConfigMin(ConfigType &min) const
287  {
288  min = min_;
289  }
290 
296  const ConfigType &getConfigMin() const { return min_; }
297 
303  ConfigType &getConfigMin() { return min_; }
304 
310  void getConfigDefault(ConfigType &config) const
311  {
312  config = default_;
313  }
314 
320  const ConfigType &getConfigDefault() const { return default_; }
321 
327  ConfigType &getConfigDefault() { return default_; }
328 
334  void setConfigMax(const ConfigType &config)
335  {
336  max_ = config;
337  PublishDescription();
338  }
339 
345  void setConfigMin(const ConfigType &config)
346  {
347  min_ = config;
348  PublishDescription();
349  }
350 
356  void setConfigDefault(const ConfigType &config)
357  {
358  default_ = config;
359  PublishDescription();
360  }
361 
367  dynamic_reconfigure::ConfigDescriptionPtr getDescriptionMessage() {
368  dynamic_reconfigure::ConfigDescriptionPtr description_message = traits::getDescriptionMessage(this);
369 
370  // Copy over min_ max_ default_
371  traits::toMessage(max_, description_message->max, this);
372  traits::toMessage(min_, description_message->min, this);
373  traits::toMessage(default_, description_message->dflt, this);
374 
375  return description_message;
376  }
377 
384  void advertise(std::string ns = std::string())
385  {
386  // shutdown publishers/service servers from previous runs
387  shutdown();
388 
389  // set default namespace
390  if (ns.empty()) {
391  if (getOwner()->getName() == "Deployer")
392  ns = "~";
393  else
394  ns = "~" + getOwner()->getName();
395  }
396 
397  // create NodeHandle
398  node_handle_ = new ros::NodeHandle(ns);
399 
400  // advertise service server and publishers
401  set_service_ = node_handle_->advertiseService("set_parameters", &Server<ConfigType>::setConfigCallback, this);
402  descr_pub_ = node_handle_->advertise<dynamic_reconfigure::ConfigDescription>("parameter_descriptions", 1, true);
403  update_pub_ = node_handle_->advertise<dynamic_reconfigure::Config>("parameter_updates", 1, true);
404 
405  // publish update once
406  PublishDescription();
407  updateConfigInternal(config_);
408  }
409 
414  void shutdown()
415  {
416  if (node_handle_) {
417  node_handle_->shutdown();
418  delete node_handle_;
419  node_handle_ = 0;
420  }
421  }
422 
428  bool updated()
429  {
430  ConfigType new_config = config_;
431  if (!updater()->configFromProperties(new_config, *(getOwner()->properties()))) return false;
432  updateConfig(new_config);
433  return true;
434  }
435 
440  void refresh()
441  {
442  RTT::os::MutexLock lock(mutex_);
443 
444  // Refresh config description (no-op unless for AutoConfig)
445  traits::refreshDescription(this);
446 
447  // Grab copys of the data from the config files. These are declared in the generated config file.
448  traits::getMin(min_, this);
449  traits::getMax(max_, this);
450  traits::getDefault(default_, this);
451 
452  // Publish the description
453  PublishDescription();
454 
455  // Add/replace min/max/default properties
456  this->properties()->remove(this->properties()->getProperty("min"));
457  this->properties()->remove(this->properties()->getProperty("max"));
458  this->properties()->remove(this->properties()->getProperty("default"));
459  this->properties()->ownProperty(new RTT::Property<RTT::PropertyBag>("min", "Minimum values as published to dynamic_reconfigure clients", traits::getDataSource(min_, this)));
460  this->properties()->ownProperty(new RTT::Property<RTT::PropertyBag>("max", "Maximum values as published to dynamic_reconfigure clients", traits::getDataSource(max_, this)));
461  this->properties()->ownProperty(new RTT::Property<RTT::PropertyBag>("default", "Default values as published to dynamic_reconfigure clients", traits::getDataSource(default_, this)));
462 
463  // Get initial values from current property settings
464  config_ = ConfigType();
465  traits::getDefault(config_, this);
466  updater()->configFromProperties(config_, *(getOwner()->properties()));
467  if (node_handle_)
468  config_.__fromServer__(*node_handle_);
469  traits::clamp(config_, this);
470 
471  // At startup we need to load the configuration with all level bits set (everything has changed).
472  RTT::PropertyBag init_config;
473  updater()->propertiesFromConfig(config_, ~0, init_config);
474 
475  // Invoke update and notification callback
476 #if !RTT_VERSION_GTE(2,8,99)
477  // Additional check for RTT < 2.9:
478  // ===============================
479  // We do not know for sure which thread is calling this method/operation, but we can check if the current
480  // thread is the same as the thread that will process the update/notify operation. If yes, we clone the
481  // underlying OperationCaller implementation and set the caller to the processing engine. In this case
482  // RTT < 2.9 should always call the operation directly as if it would be a ClientThread operation:
483  // https://github.com/orocos-toolchain/rtt/blob/toolchain-2.8/rtt/base/OperationCallerInterface.hpp#L79
484  //
485  // RTT 2.9 and above already checks the caller thread internally and therefore does not require this hack.
486  //
488  if (update_callback_impl) {
489  RTT::ExecutionEngine *engine = update_callback_impl->getMessageProcessor();
490  if (update_callback_impl->isSend() && engine && engine->getThread() && engine->getThread()->isSelf()) {
491  RTT::Logger::In in(this->getOwner()->getName() + "." + this->getName());
492  RTT::log(RTT::Debug) << "calling my own updateProperties operation from refresh()" << RTT::endlog();
493  update_callback_impl.reset(update_callback_impl->cloneI(engine));
494  update_callback_impl->call(init_config, ~0);
495  } else {
496  update_callback_(init_config, ~0);
497  }
498  }
499  RTT::base::OperationCallerBase<UpdateCallbackConstSignature>::shared_ptr update_callback_const_impl = update_callback_const_.getOperationCallerImpl();
500  if (update_callback_const_impl) {
501  RTT::ExecutionEngine *engine = update_callback_const_impl->getMessageProcessor();
502  if (update_callback_const_impl->isSend() && engine && engine->getThread() && engine->getThread()->isSelf()) {
503  RTT::Logger::In in(this->getOwner()->getName() + "." + this->getName());
504  RTT::log(RTT::Debug) << "calling my own updateProperties operation from refresh()" << RTT::endlog();
505  update_callback_const_impl.reset(update_callback_const_impl->cloneI(engine));
506  update_callback_const_impl->call(init_config, ~0);
507  } else {
508  update_callback_const_(init_config, ~0);
509  }
510  }
512  if (notify_callback_impl) {
513  RTT::ExecutionEngine *engine = notify_callback_impl->getMessageProcessor();
514  if (notify_callback_impl->isSend() && engine && engine->getThread() && engine->getThread()->isSelf()) {
515  RTT::Logger::In in(this->getOwner()->getName() + "." + this->getName());
516  RTT::log(RTT::Debug) << "calling my own notifyPropertiesUpdate operation from refresh()" << RTT::endlog();
517  notify_callback_impl.reset(notify_callback_impl->cloneI(engine));
518  notify_callback_impl->call(~0);
519  } else {
520  notify_callback_(~0);
521  }
522  }
523 #else
524  if (update_callback_.ready()) {
525  update_callback_(init_config, ~0);
526  } else if (update_callback_const_.ready()) {
527  update_callback_const_(init_config, ~0);
528  }
529  if (notify_callback_.ready()) {
530  notify_callback_(~0);
531  }
532 #endif
533 
534  updateConfigInternal(config_);
535  }
536 
542  UpdaterType *updater() const
543  {
544  if (!updater_) updater_.reset(new UpdaterType());
545  return updater_.get();
546  }
547 
553  void setUpdater(UpdaterType *updater)
554  {
555  updater_.reset(updater, null_deleter());
556  }
557 
564  {
565  update_callback_ = impl;
566  }
567 
574  {
575  notify_callback_ = impl;
576  }
577 
578 private:
579  void construct()
580  {
581  this->addOperation("advertise", &Server<ConfigType>::advertise, this)
582  .doc("Advertise this dynamic_reconfigure server at the master.")
583  .arg("namespace", "The namespace this server should be advertised in. Defaults to ~component.");
584  this->addOperation("shutdown", &Server<ConfigType>::shutdown, this)
585  .doc("Shutdown this dynamic_reconfigure server.");
586  this->addOperation("updated", &Server<ConfigType>::updated, this)
587  .doc("Notify the dynamic_reconfigure server that properties have been updated. This will update the GUI.");
588 
589  this->addOperation("refresh", &Server<ConfigType>::refresh, this)
590  .doc("Rediscover the owner's properties or update advertised min/max/default values. Call this operation after having added properties.");
591 
592  // check if owner implements the Updater interface
593  UpdaterType *updater = dynamic_cast<UpdaterType *>(getOwner());
594  if (updater) setUpdater(updater);
595 
596  // check if owner provides the updateProperties operation
597  if (getOwner() && getOwner()->provides()->hasMember("updateProperties")) {
598  RTT::OperationInterfacePart *op = getOwner()->provides()->getPart("updateProperties");
599  if (boost::dynamic_pointer_cast< RTT::base::OperationCallerBase<UpdateCallbackSignature> >(op->getLocalOperation())) {
600  update_callback_ = op;
601  } else {
602  update_callback_const_ = op;
603  }
604  } else {
605  update_callback_const_ = update_callback_default_impl_.getOperationCaller();
606  }
607 
608  // check if owner provides the notifyPropertiesUpdate operation
609  if (getOwner() && getOwner()->provides()->hasMember("notifyPropertiesUpdate")) {
610  notify_callback_ = getOwner()->provides()->getPart("notifyPropertiesUpdate");
611  }
612 
613  // update_callback_ and notify_callback_ are called from the ROS spinner thread -> set GlobalEngine as caller engine
615  update_callback_const_.setCaller(RTT::internal::GlobalEngine::Instance());
617 
618  // refresh once
619  refresh();
620  }
621 
623  if (!descr_pub_) return;
624  descr_pub_.publish(getDescriptionMessage());
625  }
626 
627  friend class DynamicReconfigureTestComponent;
628  bool setConfigCallback(dynamic_reconfigure::Reconfigure::Request &req,
629  dynamic_reconfigure::Reconfigure::Response &rsp)
630  {
631  RTT::os::MutexLock lock(mutex_);
632 
633  ConfigType new_config = config_;
634  traits::fromMessage(new_config, req.config, this);
635  traits::clamp(new_config, this);
636  uint32_t level = config_.__level__(new_config);
637 
638  RTT::PropertyBag bag;
639  if (!updater()->propertiesFromConfig(new_config, level, bag)) return false;
640  if (update_callback_.ready()) {
641  if (!update_callback_(bag, level)) return false;
642  updater()->configFromProperties(new_config, bag);
643  } else if (update_callback_const_.ready()) {
644  if (!update_callback_const_(bag, level)) return false;
645  } else {
646  return false;
647  }
648  if (notify_callback_.ready()) notify_callback_(level);
649 
650  updateConfigInternal(new_config);
651  new_config.__toMessage__(rsp.config);
652  return true;
653  }
654 
655  void updateConfigInternal(const ConfigType &config)
656  {
657  RTT::os::MutexLock lock(mutex_);
658  config_ = config;
659  if (node_handle_)
660  config_.__toServer__(*node_handle_);
661  dynamic_reconfigure::Config msg;
662  config_.__toMessage__(msg);
663 
664  if (update_pub_)
665  update_pub_.publish(msg);
666  }
667 
669  {
670  return RTT::updateProperties(*(getOwner()->properties()), bag);
671  }
672 };
673 
684 template <typename T, typename ValueType>
685 bool setProperty(const std::string &name, RTT::PropertyBag &bag, ValueType &value)
686 {
687  if (bag.getProperty(name)) {
688  RTT::Property<T> *prop = bag.getPropertyType<T>(name);
689  if (!prop) {
690  RTT::log(RTT::Error) << "Could not assign property '" << name << "': Property exists with a different type." << RTT::endlog();
691  return false;
692  }
693 
694  prop->set() = value;
695 
696  } else {
697  if (boost::is_same<T,ValueType>::value) {
698  bag.addProperty(name, value);
699  } else {
700  bag.ownProperty(new RTT::Property<T>(name, std::string(), value));
701  }
702  }
703 
704  return true;
705 }
706 
717 template <typename T, typename ValueType>
718 bool getProperty(const std::string &name, const RTT::PropertyBag &bag, ValueType &value)
719 {
720  RTT::Property<T> *prop = bag.getPropertyType<T>(name);
721  if (!prop) {
722  RTT::log(RTT::Error) << "Could not get property '" << name << "': No such property in the bag." << RTT::endlog();
723  return false;
724  }
725 
726  value = prop->rvalue();
727  return true;
728 }
729 
730 } // namespace rtt_dynamic_reconfigure
731 
732 #define RTT_DYNAMIC_RECONFIGURE_SERVICE_PLUGIN(CONFIG, NAME) \
733  extern "C" {\
734  RTT_EXPORT bool loadRTTPlugin(RTT::TaskContext* tc); \
735  bool loadRTTPlugin(RTT::TaskContext* tc) { \
736  if (tc == 0) return true; \
737  RTT::Service::shared_ptr sp( new rtt_dynamic_reconfigure::Server<CONFIG>(NAME, tc ) ); \
738  return tc->provides()->addService( sp ); \
739  } \
740  RTT_EXPORT RTT::Service::shared_ptr createService(); \
741  RTT::Service::shared_ptr createService() { \
742  RTT::Service::shared_ptr sp( new rtt_dynamic_reconfigure::Server<CONFIG>( 0 ) ); \
743  return sp; \
744  } \
745  RTT_EXPORT std::string getRTTPluginName(); \
746  std::string getRTTPluginName() { \
747  return NAME; \
748  } \
749  RTT_EXPORT std::string getRTTTargetName(); \
750  std::string getRTTTargetName() { \
751  return OROCOS_TARGET_NAME; \
752  } \
753  }
754 
755 #endif // RTT_DYNAMIC_RECONFIGURE_SERVER_H
Server(RTT::TaskContext *owner)
Definition: server.h:224
virtual os::ThreadInterface * getThread() const
bool updatePropertiesDefaultImpl(const RTT::PropertyBag &bag, uint32_t)
Definition: server.h:668
static RTT::internal::AssignableDataSource< RTT::PropertyBag >::shared_ptr getDataSource(ConfigType &config, const ServerType *server)
Definition: server.h:156
ConfigType & getConfigDefault()
Definition: server.h:327
bool( UpdateCallbackSignature)(RTT::PropertyBag &bag, uint32_t level)
Definition: server.h:61
void getConfigMin(ConfigType &min) const
Definition: server.h:286
virtual base::OperationCallerBase< Signature >::shared_ptr getOperationCaller()
bool getProperty(const std::string &name, const RTT::PropertyBag &bag, ValueType &value)
Definition: server.h:718
Property< T > * getPropertyType(const std::string &name) const
void setConfigMin(const ConfigType &config)
Definition: server.h:345
void getConfigMax(ConfigType &max) const
Definition: server.h:262
void publish(const boost::shared_ptr< M > &message) const
bool updateProperties(PropertyBag &target, const PropertyBag &source)
const OperationCallerBasePtr getOperationCallerImpl() const
RTT::OperationCaller< UpdateCallbackConstSignature > update_callback_const_
Definition: server.h:200
bool ready() const
ros::Publisher update_pub_
Definition: server.h:188
Variable opBinary s not applicable to op
virtual void set(param_t t)=0
bool setProperty(const std::string &name, RTT::PropertyBag &bag, ValueType &value)
Definition: server.h:685
void setConfigMax(const ConfigType &config)
Definition: server.h:334
std::string getName(void *handle)
static void getMin(ConfigType &min, const ServerType *)
Definition: server.h:86
void setConfigDefault(const ConfigType &config)
Definition: server.h:356
static void clamp(ConfigType &config, const ServerType *)
Definition: server.h:148
Server(const std::string &name, RTT::TaskContext *owner)
Definition: server.h:211
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
const_reference_t rvalue() const
void setCaller(ExecutionEngine *caller)
virtual bool propertiesFromConfig(ConfigType &, uint32_t, RTT::PropertyBag &)
Definition: server.h:72
boost::shared_ptr< UpdaterType > updater_
Definition: server.h:196
RTT::OperationCaller< NotifyCallbackSignature > notify_callback_
Definition: server.h:202
ros::ServiceServer set_service_
Definition: server.h:187
UpdaterType * updater() const
Definition: server.h:542
static void getMax(ConfigType &max, const ServerType *)
Definition: server.h:94
bool ownProperty(base::PropertyBase *p)
const ConfigType & getConfigDefault() const
Definition: server.h:320
boost::shared_ptr< Server< ConfigType > > shared_ptr
Definition: server.h:183
static void getDefault(ConfigType &dflt, const ServerType *)
Definition: server.h:102
static dynamic_reconfigure::ConfigDescriptionPtr getDescriptionMessage(const ServerType *)
Definition: server.h:110
const ConfigType & getConfig() const
Definition: server.h:245
static void refreshDescription(const ServerType *)
Definition: server.h:122
Property< T > & addProperty(const std::string &name, T &attr)
ConfigType & getConfigMax()
Definition: server.h:279
const ConfigType & getConfigMin() const
Definition: server.h:296
static RTT_API ExecutionEngine * Instance()
const ConfigType & getConfigMax() const
Definition: server.h:272
void setUpdateCallback(RTT::OperationInterfacePart *impl)
Definition: server.h:563
RTT::OperationCaller< UpdateCallbackSignature > update_callback_
Definition: server.h:199
void setNotificationCallback(RTT::OperationInterfacePart *impl)
Definition: server.h:573
ros::NodeHandle * node_handle_
Definition: server.h:186
bool setConfigCallback(dynamic_reconfigure::Reconfigure::Request &req, dynamic_reconfigure::Reconfigure::Response &rsp)
Definition: server.h:628
static void toMessage(ConfigType &config, dynamic_reconfigure::Config &message, const ServerType *)
Definition: server.h:131
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
Updater< ConfigType > UpdaterType
Definition: server.h:181
boost::intrusive_ptr< AssignableDataSource< T > > shared_ptr
virtual RTT_API boost::shared_ptr< base::DisposableInterface > getLocalOperation() const
RTT::os::MutexRecursive mutex_
Definition: server.h:185
bool( UpdateCallbackConstSignature)(const RTT::PropertyBag &bag, uint32_t level)
Definition: server.h:62
base::PropertyBase * getProperty(const std::string &name) const
void( NotifyCallbackSignature)(uint32_t level)
Definition: server.h:63
dynamic_reconfigure_traits< ConfigType > traits
Definition: server.h:182
ROSCONSOLE_DECL void shutdown()
virtual bool configFromProperties(ConfigType &, const RTT::PropertyBag &)
Definition: server.h:73
void setUpdater(UpdaterType *updater)
Definition: server.h:553
void getConfigDefault(ConfigType &config) const
Definition: server.h:310
reference_t set()
void advertise(std::string ns=std::string())
Definition: server.h:384
RTT::Operation< UpdateCallbackConstSignature > update_callback_default_impl_
Definition: server.h:201
void updateConfigInternal(const ConfigType &config)
Definition: server.h:655
ConfigType & getConfigMin()
Definition: server.h:303
static void fromMessage(ConfigType &config, dynamic_reconfigure::Config &message, const ServerType *)
Definition: server.h:140
dynamic_reconfigure::ConfigDescriptionPtr getDescriptionMessage()
Definition: server.h:367
static Logger & log()
void updateConfig(const ConfigType &config)
Definition: server.h:252
static Logger::LogFunction endlog()
ros::Publisher descr_pub_
Definition: server.h:189


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