server.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2009-2010, Willow Garage, Inc.
00005 *  Copyright (c) 2014, Intermodalics BVBA
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the Willow Garage nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *********************************************************************/
00035 
00036 #ifndef RTT_DYNAMIC_RECONFIGURE_SERVER_H
00037 #define RTT_DYNAMIC_RECONFIGURE_SERVER_H
00038 
00039 #include <rtt/Service.hpp>
00040 #include <rtt/TaskContext.hpp>
00041 #include <rtt/os/Mutex.hpp>
00042 #include <rtt/Logger.hpp>
00043 #include <rtt/Operation.hpp>
00044 #include <rtt/OperationCaller.hpp>
00045 
00046 #include <rtt/internal/DataSources.hpp>
00047 #include <rtt/internal/GlobalEngine.hpp>
00048 
00049 #include <ros/ros.h>
00050 
00051 #include <dynamic_reconfigure/Reconfigure.h>
00052 #include <dynamic_reconfigure/Config.h>
00053 #include <dynamic_reconfigure/ConfigDescription.h>
00054 
00055 namespace rtt_dynamic_reconfigure {
00056 
00057 template <class ConfigType> class Server;
00058 
00064 template <class ConfigType>
00065 struct Updater {
00066     virtual bool propertiesFromConfig(ConfigType &config, uint32_t level, RTT::PropertyBag &) { return false; }
00067     virtual bool configFromProperties(ConfigType &config, const RTT::PropertyBag &) { return false; }
00068 };
00069 
00070 template <class ConfigType>
00071 struct dynamic_reconfigure_traits {
00072     typedef Server<ConfigType> ServerType;
00073 
00080     static void getMin(ConfigType &min, const ServerType *) { min = ConfigType::__getMin__(); }
00081 
00088     static void getMax(ConfigType &max, const ServerType *) { max = ConfigType::__getMax__(); }
00089 
00096     static void getDefault(ConfigType &dflt, const ServerType *) { dflt = ConfigType::__getDefault__(); }
00097 
00104     static dynamic_reconfigure::ConfigDescriptionPtr getDescriptionMessage(const ServerType *) { return dynamic_reconfigure::ConfigDescriptionPtr(new dynamic_reconfigure::ConfigDescription(ConfigType::__getDescriptionMessage__())); }
00105 
00109     static const bool canRefresh = false;
00110 
00116     static void refreshDescription(const ServerType *) {}
00117 
00125     static void toMessage(ConfigType &config, dynamic_reconfigure::Config &message, const ServerType *) { config.__toMessage__(message); }
00126 
00134     static void fromMessage(ConfigType &config, dynamic_reconfigure::Config &message, const ServerType *) { config.__fromMessage__(message); }
00135 
00142     static void clamp(ConfigType &config, const ServerType *) { config.__clamp__(); }
00143 
00150     static RTT::internal::AssignableDataSource<RTT::PropertyBag>::shared_ptr getDataSource(ConfigType &config, const ServerType *server) {
00151         RTT::internal::AssignableDataSource<RTT::PropertyBag>::shared_ptr ds(new RTT::internal::ValueDataSource<RTT::PropertyBag>());
00152         if (!server->updater()->propertiesFromConfig(config, ~0, ds->set()))
00153             ds.reset();
00154         return ds;
00155     }
00156 };
00157 
00158 namespace {
00159   struct null_deleter {
00160       void operator()(const void *) const {}
00161   };
00162 }
00163 
00168 template <class ConfigType>
00169 class Server : public RTT::Service
00170 {
00171 private:
00172     typedef Updater<ConfigType> UpdaterType;
00173     typedef dynamic_reconfigure_traits<ConfigType> traits;
00174     typedef boost::shared_ptr< Server<ConfigType> > shared_ptr;
00175 
00176     RTT::os::MutexRecursive mutex_;
00177     ros::NodeHandle *node_handle_;
00178     ros::ServiceServer set_service_;
00179     ros::Publisher update_pub_;
00180     ros::Publisher descr_pub_;
00181 
00182     ConfigType config_;
00183     ConfigType min_;
00184     ConfigType max_;
00185     ConfigType default_;
00186 
00187     mutable boost::shared_ptr<UpdaterType> updater_;
00188     bool initialized_;
00189 
00190     RTT::OperationCaller<bool(const RTT::PropertyBag &source, uint32_t level)> update_callback_;
00191     RTT::OperationCaller<void(uint32_t level)> notify_callback_;
00192     RTT::Operation<bool(const RTT::PropertyBag &source, uint32_t level)> update_callback_default_impl_;
00193 
00194 public:
00201     Server(const std::string &name, RTT::TaskContext *owner)
00202         : RTT::Service(name, owner)
00203         , node_handle_(0)
00204         , update_callback_default_impl_("updateProperties", &Server<ConfigType>::updatePropertiesDefaultImpl, this, RTT::OwnThread)
00205     {
00206         construct();
00207     }
00208 
00214     Server(RTT::TaskContext *owner)
00215         : RTT::Service("reconfigure", owner)
00216         , node_handle_(0)
00217         , update_callback_default_impl_("updateProperties", &Server<ConfigType>::updatePropertiesDefaultImpl, this, RTT::OwnThread)
00218     {
00219         construct();
00220     }
00221 
00226     virtual ~Server() {
00227         shutdown();
00228     }
00229 
00235     void updateConfig(const ConfigType &config)
00236     {
00237         updateConfigInternal(config);
00238     }
00239 
00245     void getConfigMax(ConfigType &max) const
00246     {
00247         max = max_;
00248     }
00249 
00255     const ConfigType &getConfigMax() const { return max_; }
00256 
00262     ConfigType &getConfigMax() { return max_; }
00263 
00269     void getConfigMin(ConfigType &min) const
00270     {
00271         min = min_;
00272     }
00273 
00279     const ConfigType &getConfigMin() const { return min_; }
00280 
00286     ConfigType &getConfigMin() { return min_; }
00287 
00293     void getConfigDefault(ConfigType &config) const
00294     {
00295         config = default_;
00296     }
00297 
00303     const ConfigType &getConfigDefault() const { return default_; }
00304 
00310     ConfigType &getConfigDefault() { return default_; }
00311 
00317     void setConfigMax(const ConfigType &config)
00318     {
00319         max_ = config;
00320         PublishDescription();
00321     }
00322 
00328     void setConfigMin(const ConfigType &config)
00329     {
00330         min_ = config;
00331         PublishDescription();
00332     }
00333 
00339     void setConfigDefault(const ConfigType &config)
00340     {
00341         default_ = config;
00342         PublishDescription();
00343     }
00344 
00350     dynamic_reconfigure::ConfigDescriptionPtr getDescriptionMessage() {
00351         dynamic_reconfigure::ConfigDescriptionPtr description_message = traits::getDescriptionMessage(this);
00352 
00353         // Copy over min_ max_ default_
00354         traits::toMessage(max_, description_message->max, this);
00355         traits::toMessage(min_, description_message->min, this);
00356         traits::toMessage(default_, description_message->dflt, this);
00357 
00358         return description_message;
00359     }
00360 
00367     void advertise(std::string ns = std::string())
00368     {
00369         // shutdown publishers/service servers from previous runs
00370         shutdown();
00371 
00372         // set default namespace
00373         if (ns.empty()) {
00374             if (getOwner()->getName() == "Deployer")
00375                 ns = "~";
00376             else
00377                 ns = "~" + getOwner()->getName();
00378         }
00379 
00380         // create NodeHandle
00381         node_handle_ = new ros::NodeHandle(ns);
00382 
00383         // advertise service server and publishers
00384         set_service_ = node_handle_->advertiseService("set_parameters", &Server<ConfigType>::setConfigCallback, this);
00385         descr_pub_ = node_handle_->advertise<dynamic_reconfigure::ConfigDescription>("parameter_descriptions", 1, true);
00386         update_pub_ = node_handle_->advertise<dynamic_reconfigure::Config>("parameter_updates", 1, true);
00387 
00388         // publish update once
00389         PublishDescription();
00390         updateConfigInternal(config_);
00391     }
00392 
00397     void shutdown()
00398     {
00399         if (node_handle_) {
00400             node_handle_->shutdown();
00401             delete node_handle_;
00402             node_handle_ = 0;
00403         }
00404     }
00405 
00411     bool updated()
00412     {
00413         ConfigType new_config = config_;
00414         if (!updater()->configFromProperties(new_config, *(getOwner()->properties()))) return false;
00415         updateConfig(new_config);
00416         return true;
00417     }
00418 
00423     void refresh()
00424     {
00425         RTT::os::MutexLock lock(mutex_);
00426 
00427         // Refresh config description (no-op unless for AutoConfig)
00428         traits::refreshDescription(this);
00429 
00430         // Grab copys of the data from the config files.  These are declared in the generated config file.
00431         traits::getMin(min_, this);
00432         traits::getMax(max_, this);
00433         traits::getDefault(default_, this);
00434 
00435         // Publish the description
00436         PublishDescription();
00437 
00438         // Add/replace min/max/default properties
00439         this->properties()->remove(this->properties()->getProperty("min"));
00440         this->properties()->remove(this->properties()->getProperty("max"));
00441         this->properties()->remove(this->properties()->getProperty("default"));
00442         this->properties()->ownProperty(new RTT::Property<RTT::PropertyBag>("min", "Minimum values as published to dynamic_reconfigure clients", traits::getDataSource(min_, this)));
00443         this->properties()->ownProperty(new RTT::Property<RTT::PropertyBag>("max", "Maximum values as published to dynamic_reconfigure clients", traits::getDataSource(max_, this)));
00444         this->properties()->ownProperty(new RTT::Property<RTT::PropertyBag>("default", "Default values as published to dynamic_reconfigure clients", traits::getDataSource(default_, this)));
00445 
00446         // Get initial values from current property settings
00447         config_ = ConfigType();
00448         traits::getDefault(config_, this);
00449         updater()->configFromProperties(config_, *(getOwner()->properties()));
00450         if (node_handle_)
00451             config_.__fromServer__(*node_handle_);
00452         traits::clamp(config_, this);
00453 
00454         // At startup we need to load the configuration with all level bits set (everything has changed).
00455         RTT::PropertyBag init_config;
00456         updater()->propertiesFromConfig(config_, ~0, init_config);
00457         update_callback_(init_config, ~0);
00458         if (notify_callback_.ready()) notify_callback_(~0);
00459 
00460         updateConfigInternal(config_);
00461     }
00462 
00468     UpdaterType *updater() const
00469     {
00470         if (!updater_) updater_.reset(new UpdaterType());
00471         return updater_.get();
00472     }
00473 
00479     void setUpdater(UpdaterType *updater)
00480     {
00481         updater_.reset(updater, null_deleter());
00482     }
00483 
00489     void setUpdateCallback(RTT::OperationInterfacePart *impl)
00490     {
00491         update_callback_ = impl;
00492     }
00493 
00499     void setNotificationCallback(RTT::OperationInterfacePart *impl)
00500     {
00501         notify_callback_ = impl;
00502     }
00503 
00504 private:
00505     void construct()
00506     {
00507         this->addOperation("advertise", &Server<ConfigType>::advertise, this)
00508             .doc("Advertise this dynamic_reconfigure server at the master.")
00509             .arg("namespace", "The namespace this server should be advertised in. Defaults to ~component.");
00510         this->addOperation("shutdown", &Server<ConfigType>::shutdown, this)
00511             .doc("Shutdown this dynamic_reconfigure server.");
00512         this->addOperation("updated", &Server<ConfigType>::updated, this)
00513             .doc("Notify the dynamic_reconfigure server that properties have been updated. This will update the GUI.");
00514 
00515         this->addOperation("refresh", &Server<ConfigType>::refresh, this)
00516             .doc("Rediscover the owner's properties or update advertised min/max/default values. Call this operation after having added properties.");
00517 
00518         // check if owner implements the Updater interface
00519         UpdaterType *updater = dynamic_cast<UpdaterType *>(getOwner());
00520         if (updater) setUpdater(updater);
00521 
00522         // check if owner provides the updateProperties operation
00523         if (getOwner() && getOwner()->provides()->hasOperation("updateProperties")) {
00524             update_callback_ = getOwner()->provides()->getLocalOperation("updateProperties");
00525         } else {
00526             update_callback_ = update_callback_default_impl_.getOperationCaller();
00527         }
00528 
00529         // check if owner provides the notifyPropertiesUpdate operation
00530         if (getOwner() && getOwner()->provides()->hasOperation("notifyPropertiesUpdate")) {
00531             notify_callback_ = getOwner()->provides()->getLocalOperation("notifyPropertiesUpdate");
00532         }
00533 
00534         // update_callback_ and notify_callback_ are called from the ROS spinner thread -> set GlobalEngine as caller engine
00535         update_callback_.setCaller(RTT::internal::GlobalEngine::Instance());
00536         notify_callback_.setCaller(RTT::internal::GlobalEngine::Instance());
00537 
00538         // refresh once
00539         refresh();
00540     }
00541 
00542     void PublishDescription() {
00543         if (!descr_pub_) return;
00544         descr_pub_.publish(getDescriptionMessage());
00545     }
00546 
00547     bool setConfigCallback(dynamic_reconfigure::Reconfigure::Request &req,
00548                            dynamic_reconfigure::Reconfigure::Response &rsp)
00549     {
00550         RTT::os::MutexLock lock(mutex_);
00551 
00552         ConfigType new_config = config_;
00553         traits::fromMessage(new_config, req.config, this);
00554         traits::clamp(new_config, this);
00555         uint32_t level = config_.__level__(new_config);
00556 
00557         RTT::PropertyBag bag;
00558         if (!updater()->propertiesFromConfig(new_config, level, bag)) return false;
00559         if (!update_callback_.ready() || !update_callback_(bag, level)) return false;
00560         if (notify_callback_.ready()) notify_callback_(level);
00561 
00562         updateConfigInternal(new_config);
00563         new_config.__toMessage__(rsp.config);
00564         return true;
00565     }
00566 
00567     void updateConfigInternal(const ConfigType &config)
00568     {
00569         RTT::os::MutexLock lock(mutex_);
00570         config_ = config;
00571         if (node_handle_)
00572             config_.__toServer__(*node_handle_);
00573         dynamic_reconfigure::Config msg;
00574         config_.__toMessage__(msg);
00575 
00576         if (update_pub_)
00577             update_pub_.publish(msg);
00578     }
00579 
00580     bool updatePropertiesDefaultImpl(const RTT::PropertyBag &source, uint32_t)
00581     {
00582         return RTT::updateProperties(*(getOwner()->properties()), source);
00583     }
00584 };
00585 
00596 template <typename T, typename ValueType>
00597 bool setProperty(const std::string &name, RTT::PropertyBag &bag, ValueType &value)
00598 {
00599     if (bag.getProperty(name)) {
00600         RTT::Property<T> *prop = bag.getPropertyType<T>(name);
00601         if (!prop) {
00602             RTT::log(RTT::Error) << "Could not assign property '" << name << "': Property exists with a different type." << RTT::endlog();
00603             return false;
00604         }
00605 
00606         prop->set() = value;
00607 
00608     } else {
00609         if (boost::is_same<T,ValueType>::value) {
00610             bag.addProperty(name, value);
00611         } else {
00612             bag.ownProperty(new RTT::Property<T>(name, std::string(), value));
00613         }
00614     }
00615 
00616     return true;
00617 }
00618 
00629 template <typename T, typename ValueType>
00630 bool getProperty(const std::string &name, const RTT::PropertyBag &bag, ValueType &value)
00631 {
00632     RTT::Property<T> *prop = bag.getPropertyType<T>(name);
00633     if (!prop) {
00634         RTT::log(RTT::Error) << "Could not get property '" << name << "': No such property in the bag." << RTT::endlog();
00635         return false;
00636     }
00637 
00638     value = prop->rvalue();
00639     return true;
00640 }
00641 
00642 } // namespace rtt_dynamic_reconfigure
00643 
00644 #define RTT_DYNAMIC_RECONFIGURE_SERVICE_PLUGIN(CONFIG, NAME) \
00645     extern "C" {\
00646         RTT_EXPORT bool loadRTTPlugin(RTT::TaskContext* tc);  \
00647         bool loadRTTPlugin(RTT::TaskContext* tc) {    \
00648             if (tc == 0) return true; \
00649             RTT::Service::shared_ptr sp( new rtt_dynamic_reconfigure::Server<CONFIG>(NAME, tc ) ); \
00650             return tc->provides()->addService( sp ); \
00651         } \
00652         RTT_EXPORT RTT::Service::shared_ptr createService();  \
00653         RTT::Service::shared_ptr createService() {    \
00654             RTT::Service::shared_ptr sp( new rtt_dynamic_reconfigure::Server<CONFIG>( 0 ) ); \
00655             return sp; \
00656         } \
00657         RTT_EXPORT std::string getRTTPluginName(); \
00658         std::string getRTTPluginName() { \
00659             return NAME; \
00660         } \
00661         RTT_EXPORT std::string getRTTTargetName(); \
00662         std::string getRTTTargetName() { \
00663             return OROCOS_TARGET_NAME; \
00664         } \
00665     }
00666 
00667 #endif // RTT_DYNAMIC_RECONFIGURE_SERVER_H


rtt_dynamic_reconfigure
Author(s): Johannes Meyer
autogenerated on Wed Sep 16 2015 06:59:29