auto_config.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2014, Intermodalics BVBA
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Intermodalics BVBA nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #include <rtt_dynamic_reconfigure/auto_config.h>
00036 #include <rtt/Property.hpp>
00037 #include <rtt/internal/DataSources.hpp>
00038 #include <rtt/types/PropertyComposition.hpp>
00039 
00040 #include <climits>
00041 #include <cfloat>
00042 
00043 #include <boost/thread/locks.hpp>
00044 
00045 #include <dynamic_reconfigure/config_tools.h>
00046 
00047 namespace rtt_dynamic_reconfigure {
00048 
00049 using namespace dynamic_reconfigure;
00050 
00056 class AutoConfigDataSource
00057     : public RTT::internal::AssignableDataSource<RTT::PropertyBag>
00058 {
00059 protected:
00060     AutoConfig mdata;
00061 
00062 public:
00063     ~AutoConfigDataSource() {}
00064 
00065     typedef boost::intrusive_ptr<AutoConfigDataSource> shared_ptr;
00066 
00067     AutoConfigDataSource(const AutoConfig &data) : mdata(data) {}
00068     AutoConfigDataSource() {}
00069 
00070     RTT::internal::DataSource<RTT::PropertyBag>::result_t get() const { return mdata; }
00071     RTT::internal::DataSource<RTT::PropertyBag>::result_t value() const { return mdata; }
00072 
00073     void set( typename AssignableDataSource<RTT::PropertyBag>::param_t t ) { mdata = t; }
00074     AutoConfig& set() { return mdata; }
00075     const AutoConfig& rvalue() const { return mdata; }
00076 
00077     virtual AutoConfigDataSource* clone() const { return new AutoConfigDataSource(mdata); }
00078 
00079     /* copied from ValueDataSource<T>::copy() in DataSources.inl */
00080     virtual AutoConfigDataSource* copy( std::map<const RTT::base::DataSourceBase*, RTT::base::DataSourceBase*>& replace ) const
00081     {
00082         // if somehow a copy exists, return the copy, otherwise return this (see Attribute copy)
00083         if ( replace[this] != 0 ) {
00084             assert ( dynamic_cast<AutoConfigDataSource*>( replace[this] ) == static_cast<AutoConfigDataSource*>( replace[this] ) );
00085             return static_cast<AutoConfigDataSource*>( replace[this] );
00086         }
00087         // Other pieces in the code rely on insertion in the map :
00088         replace[this] = const_cast<AutoConfigDataSource*>(this);
00089         // return this instead of a copy.
00090         return const_cast<AutoConfigDataSource*>(this);
00091     }
00092 
00097     static AutoConfigDataSource* narrow(RTT::base::DataSourceBase* dsb) {
00098         AutoConfigDataSource* ret = dynamic_cast< AutoConfigDataSource* >( dsb );
00099         return ret;
00100     }
00101 };
00102 
00103 AutoConfig::AutoConfig()
00104 {
00105 }
00106 
00107 AutoConfig::AutoConfig(const RTT::PropertyBag &bag)
00108 {
00109     this->fromProperties(bag);
00110 }
00111 
00112 AutoConfig::~AutoConfig()
00113 {
00114 }
00115 
00116 // default type
00117 template <typename T> struct PropertyTypeInfo {
00118     typedef std::string dynamic_reconfigure_type;
00119     static std::string getType() { return "str"; }
00120     static bool hasLimits() { return false; }
00121     static T getMin() { return std::numeric_limits<T>::lowest(); }
00122     static T getMax() { return std::numeric_limits<T>::max(); }
00123 };
00124 
00125 template <> struct PropertyTypeInfo<bool>
00126 {
00127     typedef bool dynamic_reconfigure_type;
00128     static std::string getType() { return "bool"; }
00129     static bool hasLimits() { return false; }
00130     static bool getMin() { return false; }
00131     static bool getMax() { return true; }
00132 };
00133 
00134 template <> struct PropertyTypeInfo<int>
00135 {
00136     typedef int dynamic_reconfigure_type;
00137     static std::string getType() { return "int"; }
00138     static bool hasLimits() { return true; }
00139     static int getMin() { return INT_MIN; }
00140     static int getMax() { return INT_MAX; }
00141 };
00142 
00143 template <> struct PropertyTypeInfo<unsigned int>
00144 {
00145     typedef int dynamic_reconfigure_type;
00146     static std::string getType() { return "int"; }
00147     static bool hasLimits() { return true; }
00148     static int getMin() { return 0; }
00149     static int getMax() { return INT_MAX; }
00150 };
00151 
00152 template <> struct PropertyTypeInfo<std::string>
00153 {
00154     typedef std::string dynamic_reconfigure_type;
00155     static std::string getType() { return "str"; }
00156     static bool hasLimits() { return false; }
00157     static std::string getMin() { return ""; }
00158     static std::string getMax() { return ""; }
00159 };
00160 
00161 template <> struct PropertyTypeInfo<double>
00162 {
00163     typedef double dynamic_reconfigure_type;
00164     static std::string getType() { return "double"; }
00165     static bool hasLimits() { return true; }
00166     static double getMin() { return -DBL_MAX; }
00167     static double getMax() { return  DBL_MAX; }
00168 };
00169 
00170 template <> struct PropertyTypeInfo<float>
00171 {
00172     typedef double dynamic_reconfigure_type;
00173     static std::string getType() { return "double"; }
00174     static bool hasLimits() { return true; }
00175     static double getMin() { return -FLT_MAX; }
00176     static double getMax() { return  FLT_MAX; }
00177 };
00178 
00179 static AutoConfig *getAutoConfigFromProperty(const RTT::base::PropertyBase *pb)
00180 {
00181     const RTT::Property<RTT::PropertyBag> *prop = dynamic_cast<const RTT::Property<RTT::PropertyBag> *>(pb);
00182     if (!prop) return 0;
00183     AutoConfigDataSource *ds = AutoConfigDataSource::narrow(prop->getDataSource().get());
00184     if (!ds) return 0;
00185     return &(ds->set());
00186 }
00187 
00188 template <typename T>
00189 static bool propertyFromMessage(AutoConfig &config, Config &msg, const RTT::base::PropertyBase *sample, const std::string &param_name)
00190 {
00191     const RTT::Property<T> *sample_prop = dynamic_cast<const RTT::Property<T> *>(sample);
00192     if (!sample_prop) return false;
00193 
00194     typename PropertyTypeInfo<T>::dynamic_reconfigure_type value;
00195     if (!ConfigTools::getParameter(msg, param_name, value)) return false;
00196 
00197     RTT::Property<T> *prop = config.getPropertyType<T>(sample->getName());
00198     if (!prop) {
00199         prop = sample_prop->create();
00200         config.ownProperty(prop);
00201     }
00202     prop->set(value);
00203     return true;
00204 }
00205 
00206 bool AutoConfig::__fromMessage__(Config &msg, const AutoConfig &sample)
00207 {
00208     return __fromMessage__(*this, msg, sample);
00209 }
00210 
00211 bool AutoConfig::__fromMessage__(AutoConfig &config, Config &msg, const AutoConfig &sample)
00212 {
00213     // get group state
00214     config.prefix_ = sample.prefix_;
00215     config.name = sample.name;
00216     config.id = sample.id;
00217     config.parent = sample.parent;
00218     dynamic_reconfigure::ConfigTools::getGroupState(msg, config.name, config);
00219 
00220     // iterate over all properties in sample
00221     bool result = true;
00222     for(RTT::PropertyBag::const_iterator i = sample.begin(); i != sample.end(); ++i) {
00223         RTT::base::PropertyBase *pb = config.getProperty((*i)->getName());
00224         std::string param_name = config.prefix_ + (*i)->getName();
00225 
00226         // For sub groups, add a sub config to *this and recurse...
00227         const AutoConfig *sample_sub = getAutoConfigFromProperty(*i);
00228         if (sample_sub) {
00229             RTT::Property<RTT::PropertyBag> *sub = config.getPropertyType<RTT::PropertyBag>((*i)->getName());
00230             AutoConfigDataSource *ds;
00231             if (sub) {
00232                 ds = AutoConfigDataSource::narrow(sub->getDataSource().get());
00233             } else {
00234                 ds = new AutoConfigDataSource();
00235                 sub = new RTT::Property<RTT::PropertyBag>((*i)->getName(), (*i)->getDescription(), AutoConfigDataSource::shared_ptr(ds));
00236                 config.ownProperty(sub);
00237             }
00238 
00239             if (ds && __fromMessage__(ds->set(), msg, *sample_sub))
00240                 continue;
00241         }
00242 
00243         // search parameter in Config message
00244         bool param_found = false;
00245         for(Config::_bools_type::const_iterator n = msg.bools.begin(); n != msg.bools.end(); ++n) {
00246             if (n->name == param_name) param_found = true;
00247         }
00248         for(Config::_ints_type::const_iterator n = msg.ints.begin(); n != msg.ints.end(); ++n) {
00249             if (n->name == param_name) param_found = true;
00250         }
00251         for(Config::_strs_type::const_iterator n = msg.strs.begin(); n != msg.strs.end(); ++n) {
00252             if (n->name == param_name) param_found = true;
00253         }
00254         for(Config::_doubles_type::const_iterator n = msg.doubles.begin(); n != msg.doubles.end(); ++n) {
00255             if (n->name == param_name) param_found = true;
00256         }
00257         if (!param_found) continue;
00258 
00259         // get parameter value from Config message
00260         if (
00261             propertyFromMessage<bool>(config, msg, *i, param_name) ||
00262             propertyFromMessage<int>(config, msg, *i, param_name) ||
00263             propertyFromMessage<unsigned int>(config, msg, *i, param_name) ||
00264             propertyFromMessage<std::string>(config, msg, *i, param_name) ||
00265             propertyFromMessage<double>(config, msg, *i, param_name) ||
00266             propertyFromMessage<float>(config, msg, *i, param_name)
00267            ) continue;
00268 
00269         result = false;
00270     }
00271 
00272     return result;
00273 }
00274 
00275 template <typename T>
00276 static bool propertyToMessage(Config &msg, const RTT::base::PropertyBase *pb, const std::string &_prefix)
00277 {
00278     const RTT::Property<T> *prop = dynamic_cast<const RTT::Property<T> *>(pb);
00279     if (!prop) return false;
00280 
00281     typename PropertyTypeInfo<T>::dynamic_reconfigure_type value = prop->get();
00282     ConfigTools::appendParameter(msg, _prefix + pb->getName(), value);
00283     return true;
00284 }
00285 
00286 void AutoConfig::__toMessage__(Config &msg) const
00287 {
00288     __toMessage__(*this, msg);
00289 }
00290 
00291 void AutoConfig::__toMessage__(const AutoConfig &config, Config &msg)
00292 {
00293     // add group state
00294     dynamic_reconfigure::ConfigTools::appendGroup(msg, config.name, config.id, config.parent, config);
00295 
00296     // iterate over all properties
00297     bool result = true;
00298     for(RTT::PropertyBag::const_iterator i = config.begin(); i != config.end(); ++i) {
00299         if (propertyToMessage<bool>(msg, *i, config.prefix_) ||
00300             propertyToMessage<int>(msg, *i, config.prefix_) ||
00301             propertyToMessage<unsigned int>(msg, *i, config.prefix_) ||
00302             propertyToMessage<std::string>(msg, *i, config.prefix_) ||
00303             propertyToMessage<double>(msg, *i, config.prefix_) ||
00304             propertyToMessage<float>(msg, *i, config.prefix_)
00305            ) continue;
00306 
00307         // test if *i has type AutoConfig
00308         const AutoConfig *sub = getAutoConfigFromProperty(*i);
00309         if (sub) {
00310             __toMessage__(*sub, msg);
00311             continue;
00312         }
00313 
00314         result = false;
00315     }
00316 }
00317 
00318 void AutoConfig::__toServer__(const ros::NodeHandle &nh) const
00319 {
00320 
00321 }
00322 
00323 void AutoConfig::__fromServer__(const ros::NodeHandle &nh)
00324 {
00325 
00326 }
00327 
00328 void AutoConfig::__clamp__(const ServerType *server)
00329 {
00330     const AutoConfig &min = server->getConfigMin();
00331     const AutoConfig &max = server->getConfigMax();
00332 
00333     // TODO: clamp values
00334 }
00335 
00336 uint32_t AutoConfig::__level__(const AutoConfig &config) const
00337 {
00338     return 0;
00339 }
00340 
00341 bool AutoConfig::updateProperties(RTT::PropertyBag &target) const
00342 {
00343     RTT::PropertyBag composed;
00344     if (!RTT::types::composePropertyBag(*this, composed)) return false;
00345     return RTT::updateProperties(target, composed);
00346 }
00347 
00348 bool AutoConfig::fromProperties(const RTT::PropertyBag &source)
00349 {
00350     RTT::PropertyBag decomposed;
00351     if (!RTT::types::decomposePropertyBag(source, decomposed)) return false;
00352 
00353     for(RTT::PropertyBag::const_iterator i = decomposed.begin(); i != decomposed.end(); ++i) {
00354         RTT::base::PropertyBase *pb = this->getProperty((*i)->getName());
00355         if (pb) {
00356             pb->update(*i);
00357             continue;
00358         }
00359 
00360         RTT::Property<RTT::PropertyBag> *sub = dynamic_cast<RTT::Property<RTT::PropertyBag> *>(*i);
00361         if (sub) {
00362             AutoConfigDataSource *ds = new AutoConfigDataSource(sub->rvalue());
00363             ds->set().setType(sub->rvalue().getType());
00364             this->ownProperty(new RTT::Property<RTT::PropertyBag>(sub->getName(), sub->getDescription(), ds));
00365             continue;
00366         } else {
00367             this->ownProperty((*i)->clone());
00368         }
00369     }
00370 
00371     return true;
00372 }
00373 
00374 template <typename T>
00375 static bool buildParamDescription(const RTT::base::PropertyBase *pb, const std::string &prefix, Group::_parameters_type& params, AutoConfig& dflt, AutoConfig& min, AutoConfig& max)
00376 {
00377     const RTT::Property<T> *prop = dynamic_cast<const RTT::Property<T> *>(pb);
00378     if (!prop) return false;
00379 
00380     ParamDescription param;
00381     param.name = prefix + pb->getName();
00382     param.type = PropertyTypeInfo<T>::getType();
00383     param.description = pb->getDescription();
00384     params.push_back(param);
00385 
00386     // get current value as default
00387     if (!dflt.getProperty(pb->getName())) {
00388         RTT::Property<T> *dflt_prop = prop->create();
00389         dflt_prop->set(prop->get());
00390         dflt.ownProperty(dflt_prop);
00391     }
00392 
00393     // get minimum/maximum value
00394     if (!min.getProperty(pb->getName())) {
00395         RTT::Property<T> *min_prop = prop->create();
00396         min_prop->set(PropertyTypeInfo<T>::getMin());
00397         min.ownProperty(min_prop);
00398     }
00399     if (!max.getProperty(pb->getName())) {
00400         RTT::Property<T> *max_prop = prop->create();
00401         max_prop->set(PropertyTypeInfo<T>::getMax());
00402         max.ownProperty(max_prop);
00403     }
00404 
00405     return true;
00406 }
00407 
00408 static void buildGroupDescription(RTT::TaskContext *owner, const RTT::PropertyBag &bag, ConfigDescription& config_description, AutoConfig& dflt, AutoConfig& min, AutoConfig& max, const std::string &prefix, const std::string &name, const std::string &type, int32_t parent, int32_t id)
00409 {
00410     std::size_t group_index = config_description.groups.size();
00411     config_description.groups.push_back(Group());
00412 
00413     Group &group = config_description.groups[group_index];
00414     group.name = name.empty() ? "Default" : name;
00415     group.type = type;
00416     group.parent = parent;
00417     group.id = id;
00418 
00419     dflt.prefix_ = prefix;
00420     dflt.name = group.name;
00421     dflt.type = group.type;
00422     dflt.parent = group.parent;
00423     dflt.id = group.id;
00424     dflt.state = true;
00425 
00426     min.prefix_ = prefix;
00427     min.name = group.name;
00428     min.type = group.type;
00429     min.parent = group.parent;
00430     min.id = group.id;
00431     min.state = true;
00432 
00433     max.prefix_ = prefix;
00434     max.name = group.name;
00435     max.type = group.type;
00436     max.parent = group.parent;
00437     max.id = group.id;
00438     max.state = true;
00439 
00440     // for loop might invalidate group reference -> use index group_index instead
00441     for(RTT::PropertyBag::const_iterator i = bag.begin(); i != bag.end(); ++i) {
00442         if (buildParamDescription<bool>(*i, prefix, config_description.groups[group_index].parameters, dflt, min, max) ||
00443             buildParamDescription<int>(*i, prefix, config_description.groups[group_index].parameters, dflt, min, max) ||
00444             buildParamDescription<unsigned int>(*i, prefix, config_description.groups[group_index].parameters, dflt, min, max) ||
00445             buildParamDescription<std::string>(*i, prefix, config_description.groups[group_index].parameters, dflt, min, max) ||
00446             buildParamDescription<double>(*i, prefix, config_description.groups[group_index].parameters, dflt, min, max) ||
00447             buildParamDescription<float>(*i, prefix, config_description.groups[group_index].parameters, dflt, min, max)
00448            ) continue;
00449 
00450         const RTT::Property<RTT::PropertyBag> *sub = dynamic_cast<RTT::Property<RTT::PropertyBag> *>(*i);
00451         if (sub) {
00452             AutoConfig *sub_dflt = getAutoConfigFromProperty(dflt.getProperty(sub->getName()));
00453             if (!sub_dflt) {
00454                 AutoConfigDataSource *ds = new AutoConfigDataSource();
00455                 sub_dflt = &(ds->set());
00456                 sub_dflt->setType(sub->rvalue().getType());
00457                 dflt.ownProperty(new RTT::Property<RTT::PropertyBag>(sub->getName(), sub->getDescription(), ds));
00458             }
00459 
00460             AutoConfig *sub_min = getAutoConfigFromProperty(min.getProperty(sub->getName()));
00461             if (!sub_min) {
00462                 AutoConfigDataSource *ds = new AutoConfigDataSource();
00463                 sub_min = &(ds->set());
00464                 sub_min->setType(sub->rvalue().getType());
00465                 min.ownProperty(new RTT::Property<RTT::PropertyBag>(sub->getName(), sub->getDescription(), ds));
00466             }
00467 
00468             AutoConfig *sub_max = getAutoConfigFromProperty(max.getProperty(sub->getName()));
00469             if (!sub_max) {
00470                 AutoConfigDataSource *ds = new AutoConfigDataSource();
00471                 sub_max = &(ds->set());
00472                 sub_max->setType(sub->rvalue().getType());
00473                 max.ownProperty(new RTT::Property<RTT::PropertyBag>(sub->getName(), sub->getDescription(), ds));
00474             }
00475 
00476             buildGroupDescription(owner, sub->rvalue(), config_description, *sub_dflt, *sub_min, *sub_max, prefix + sub->getName() + "__", prefix + sub->getName(), "", config_description.groups[group_index].id, ++id);
00477         }
00478     }
00479 }
00480 
00481 std::map<const AutoConfig::ServerType *, AutoConfig::CachePtr> AutoConfig::cache_;
00482 boost::shared_mutex AutoConfig::cache_mutex_;
00483 
00484 void AutoConfig::buildCache(const ServerType *server, RTT::TaskContext *owner)
00485 {
00486     RTT::PropertyBag decomposed;
00487     if (!RTT::types::decomposePropertyBag(*(owner->properties()), decomposed)) {
00488         RTT::log(RTT::Error) << "Failed to decompose properties of '" << owner->getName() << "' for dynamic_reconfigure. Properties with custom types will not be available for reconfiguration." << RTT::endlog();
00489         decomposed = *(owner->properties());
00490     }
00491 
00492     boost::upgrade_lock<boost::shared_mutex> upgrade_lock(cache_mutex_);
00493     if (upgrade_lock.owns_lock())
00494     {
00495         boost::upgrade_to_unique_lock<boost::shared_mutex> unique_lock(upgrade_lock);
00496         CachePtr& cache = cache_[server];
00497         if (!cache) cache.reset(new Cache());
00498         cache->description_message_.reset(new ConfigDescription);
00499         buildGroupDescription(owner, decomposed, *(cache->description_message_), cache->default_, cache->min_, cache->max_, "", "", "", 0, 0);
00500     }
00501 }
00502 
00503 dynamic_reconfigure::ConfigDescriptionPtr AutoConfig::__getDescriptionMessage__(const ServerType *server)
00504 {
00505     boost::shared_lock<boost::shared_mutex> lock(cache_mutex_);
00506     if (!cache_.count(server)) buildCache(server, server->getOwner());
00507     return cache_.at(server)->description_message_;
00508 }
00509 
00510 const AutoConfig &AutoConfig::__getDefault__(const ServerType *server)
00511 {
00512     boost::shared_lock<boost::shared_mutex> lock(cache_mutex_);
00513     if (!cache_.count(server)) buildCache(server, server->getOwner());
00514     return cache_.at(server)->default_;
00515 }
00516 
00517 const AutoConfig &AutoConfig::__getMax__(const ServerType *server)
00518 {
00519     boost::shared_lock<boost::shared_mutex> lock(cache_mutex_);
00520     if (!cache_.count(server)) buildCache(server, server->getOwner());
00521     return cache_.at(server)->max_;
00522 }
00523 
00524 const AutoConfig &AutoConfig::__getMin__(const ServerType *server)
00525 {
00526     boost::shared_lock<boost::shared_mutex> lock(cache_mutex_);
00527     if (!cache_.count(server)) buildCache(server, server->getOwner());
00528     return cache_.at(server)->min_;
00529 }
00530 
00531 void AutoConfig::__refreshDescription__(const ServerType *server)
00532 {
00533     buildCache(server, server->getOwner());
00534 }
00535 
00536 } // namespace rtt_dynamic_reconfigure


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