property_manager.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00030 #include "property_manager.h"
00031 #include "property.h"
00032 #include "rviz/properties/property_tree_widget.h"
00033 
00034 #include <ros/console.h>
00035 
00036 #include "config.h"
00037 
00038 namespace rviz
00039 {
00040 
00041 PropertyManager::PropertyManager()
00042 : grid_(0)
00043 , default_user_data_(0)
00044 {
00045 }
00046 
00047 PropertyManager::~PropertyManager()
00048 {
00049   clear();
00050 }
00051 
00052 void PropertyManager::addProperty(const PropertyBasePtr& property, const std::string& name, const std::string& prefix, void* user_data)
00053 {
00054   bool inserted = properties_.insert( std::make_pair( std::make_pair(prefix, name), property ) ).second;
00055   ROS_ASSERT(inserted);
00056 
00057   if (!user_data)
00058   {
00059     user_data = default_user_data_;
00060   }
00061 
00062   property->setUserData( user_data );
00063 
00064   // "connect" the property's changed() callback to this->propertySet().
00065   property->manager_ = this;
00066 
00067   if (config_ && property->getSave())
00068   {
00069     property->loadFromConfig(config_.get());
00070   }
00071 
00072   if (grid_)
00073   {
00074     property->setPropertyTreeWidget(grid_);
00075     property->writeToGrid();
00076   }
00077 
00078   if( property->getSave() )
00079   {
00080     Q_EMIT configChanged();
00081   }
00082 }
00083 
00084 StatusPropertyWPtr PropertyManager::createStatus(const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, void* user_data)
00085 {
00086   StatusPropertyPtr prop(new StatusProperty(name, prefix, parent, user_data));
00087   addProperty(prop, name, prefix, user_data);
00088 
00089   return StatusPropertyWPtr(prop);
00090 }
00091 
00092 CategoryPropertyWPtr PropertyManager::createCategory(const std::string& name, const std::string& prefix, const CategoryPropertyWPtr& parent, void* user_data)
00093 {
00094   CategoryPropertyPtr category(new CategoryProperty(name, name, prefix, parent, CategoryProperty::Getter(), CategoryProperty::Setter(), false));
00095   category->setSave( false );
00096   addProperty(category, name, prefix, user_data);
00097 
00098   return CategoryPropertyWPtr(category);
00099 }
00100 
00101 CategoryPropertyWPtr PropertyManager::createCheckboxCategory(const std::string& label, const std::string& name, const std::string& prefix, const boost::function<bool(void)>& getter,
00102                                                              const boost::function<void(bool)>& setter, const CategoryPropertyWPtr& parent, void* user_data)
00103 {
00104   CategoryPropertyPtr category(new CategoryProperty(label, name, prefix, parent, getter, setter, true));
00105   addProperty(category, name, prefix, user_data);
00106 
00107   return CategoryPropertyWPtr(category);
00108 }
00109 
00110 void PropertyManager::update()
00111 {
00112   S_PropertyBaseWPtr local_props;
00113   {
00114     boost::mutex::scoped_lock lock(changed_mutex_);
00115 
00116     local_props.swap(changed_properties_);
00117   }
00118 
00119   if (!local_props.empty())
00120   {
00121     S_PropertyBaseWPtr::iterator it = local_props.begin();
00122     S_PropertyBaseWPtr::iterator end = local_props.end();
00123     for (; it != end; ++it)
00124     {
00125       PropertyBasePtr property = it->lock();
00126       if (property)
00127       {
00128         if (grid_)
00129         {
00130           property->writeToGrid();
00131         }
00132 
00133         if (config_ && property->getSave())
00134         {
00135           property->saveToConfig(config_.get());
00136         }
00137       }
00138     }
00139 
00140     if (grid_)
00141     {
00142       grid_->update();
00143     }
00144   }
00145 }
00146 
00147 void PropertyManager::deleteProperty( const PropertyBasePtr& property )
00148 {
00149   if ( !property )
00150   {
00151     return;
00152   }
00153 
00154   // "disconnect" from the property's changed() callback.
00155   property->manager_ = 0;
00156 
00157   M_Property::iterator it = properties_.begin();
00158   M_Property::iterator end = properties_.end();
00159   for (; it != end; ++it)
00160   {
00161     if (it->second == property)
00162     {
00163       // search for any children of this property, and delete them as well
00164       deleteChildren( it->second );
00165 
00166       properties_.erase( it );
00167 
00168       break;
00169     }
00170   }
00171   if( property->getSave() )
00172   {
00173     Q_EMIT configChanged();
00174   }
00175 }
00176 
00177 void PropertyManager::deleteProperty( const std::string& name, const std::string& prefix )
00178 {
00179   M_Property::iterator found_it = properties_.find( std::make_pair( prefix, name ) );
00180   ROS_ASSERT( found_it != properties_.end() );
00181 
00182   // search for any children of this property, and delete them as well
00183   deleteChildren( found_it->second );
00184 
00185   if( found_it->second )
00186   {
00187     // "disconnect" from the property's changed() callback.
00188     found_it->second->manager_ = 0;
00189   }
00190 
00191   properties_.erase( found_it );
00192 
00193   if( found_it->second->getSave() )
00194   {
00195     Q_EMIT configChanged();
00196   }
00197 }
00198 
00199 void PropertyManager::changePrefix(const std::string& old_prefix, const std::string& new_prefix)
00200 {
00201   // This kind of sucks... because properties are split into name + prefix, can't just lookup based on the prefix
00202   // so we have to iterate through
00203   M_Property to_add;
00204   std::vector<M_Property::iterator> to_delete;
00205   bool savable_changed = false;
00206   M_Property::iterator it = properties_.begin();
00207   M_Property::iterator end = properties_.end();
00208   for (; it != end; ++it)
00209   {
00210     const std::pair<std::string, std::string>& key = it->first;
00211     const PropertyBasePtr& prop = it->second;
00212 
00213     // We want to get everything that started with the old prefix, not just those that are an exact match
00214     size_t pos = key.first.find(old_prefix);
00215     if (pos == 0)
00216     {
00217       std::string np = new_prefix + key.first.substr(old_prefix.size());
00218       prop->setPrefix(np);
00219       to_add[std::make_pair(np, key.second)] = prop;
00220       to_delete.push_back(it);
00221       if( prop->getSave() )
00222       {
00223         savable_changed = true;
00224       }
00225     }
00226   }
00227 
00228   for (size_t i = 0; i < to_delete.size(); ++i)
00229   {
00230     properties_.erase(to_delete[i]);
00231   }
00232 
00233   properties_.insert(to_add.begin(), to_add.end());
00234 
00235   if( savable_changed )
00236   {
00237     Q_EMIT configChanged();
00238   }
00239 }
00240 
00241 void PropertyManager::deleteChildren( const PropertyBasePtr& property )
00242 {
00243   if (!property)
00244   {
00245     return;
00246   }
00247 
00248   std::set<PropertyBasePtr> to_delete;
00249 
00250   M_Property::iterator prop_it = properties_.begin();
00251   M_Property::iterator prop_end = properties_.end();
00252   for ( ; prop_it != prop_end; ++prop_it )
00253   {
00254     const PropertyBasePtr& child = prop_it->second;
00255 
00256     PropertyBaseWPtr parent = child->getParent();
00257     if ( parent.lock() == property )
00258     {
00259       to_delete.insert( child );
00260     }
00261   }
00262 
00263   std::set<PropertyBasePtr>::iterator del_it = to_delete.begin();
00264   std::set<PropertyBasePtr>::iterator del_end = to_delete.end();
00265   for ( ; del_it != del_end; ++del_it )
00266   {
00267     deleteProperty( *del_it );
00268   }
00269 
00270   to_delete.clear();
00271 }
00272 
00273 void PropertyManager::deleteByUserData( void* user_data )
00274 {
00275   std::set<PropertyBasePtr> to_delete;
00276 
00277   M_Property::iterator it = properties_.begin();
00278   M_Property::iterator end = properties_.end();
00279   for ( ; it != end; ++it )
00280   {
00281     const PropertyBasePtr& property = it->second;
00282 
00283     if ( property->getUserData() == user_data )
00284     {
00285       PropertyBasePtr parent = property->getParent().lock();
00286       if ( !parent || parent->getUserData() != user_data )
00287       {
00288         to_delete.insert( property );
00289       }
00290     }
00291   }
00292 
00293   std::set<PropertyBasePtr>::iterator prop_it = to_delete.begin();
00294   std::set<PropertyBasePtr>::iterator prop_end = to_delete.end();
00295   for ( ; prop_it != prop_end; ++prop_it )
00296   {
00297     deleteProperty( *prop_it );
00298   }
00299 }
00300 
00301 void PropertyManager::propertySet( const PropertyBasePtr& property )
00302 {
00303   boost::mutex::scoped_lock lock(changed_mutex_);
00304 
00305   changed_properties_.insert(property);
00306 }
00307 
00308 void PropertyManager::emitConfigChanged()
00309 {
00310   Q_EMIT configChanged();
00311 }
00312 
00313 void PropertyManager::save(const boost::shared_ptr<Config>& config)
00314 {
00315   M_Property::iterator it = properties_.begin();
00316   M_Property::iterator end = properties_.end();
00317   for ( ; it != end; ++it )
00318   {
00319     const PropertyBasePtr& property = it->second;
00320 
00321     if ( property->getSave() )
00322     {
00323       property->saveToConfig( config.get() );
00324     }
00325   }
00326 }
00327 
00328 void PropertyManager::load(const boost::shared_ptr<Config>& config, const StatusCallback& cb)
00329 {
00330   config_ = config;
00331 
00332   M_Property::iterator it = properties_.begin();
00333   M_Property::iterator end = properties_.end();
00334   for ( ; it != end; ++it )
00335   {
00336     const PropertyBasePtr& property = it->second;
00337 
00338     if ( property->getSave() )
00339     {
00340       std::stringstream ss;
00341       ss << "Loading property [" << property->getPrefix() + property->getName() << "]";
00342       ROS_DEBUG_STREAM_NAMED("properties", ss.str());
00343 
00344       if (cb)
00345       {
00346         cb(ss.str());
00347       }
00348 
00349       property->loadFromConfig( config.get() );
00350     }
00351   }
00352 
00353   if( grid_ )
00354   {
00355     grid_->update();
00356   }
00357 }
00358 
00359 void PropertyManager::setPropertyTreeWidget(PropertyTreeWidget* grid)
00360 {
00361   ROS_ASSERT(!grid_);
00362   ROS_ASSERT(grid);
00363 
00364   grid_ = grid;
00365 
00366   M_Property::iterator it = properties_.begin();
00367   M_Property::iterator end = properties_.end();
00368   for (; it != end; ++it)
00369   {
00370     const PropertyBasePtr& property = it->second;
00371     property->setPropertyTreeWidget(grid_);
00372     property->writeToGrid();
00373   }
00374 }
00375 
00376 void PropertyManager::refreshAll()
00377 {
00378   ROS_ASSERT(grid_);
00379 
00380   M_Property::iterator it = properties_.begin();
00381   M_Property::iterator end = properties_.end();
00382   for (; it != end; ++it)
00383   {
00384     propertySet(it->second);
00385   }
00386 
00387   update();
00388 }
00389 
00390 void PropertyManager::clear()
00391 {
00392   properties_.clear();
00393 }
00394 
00395 } // end namespace rviz


rviz
Author(s): Dave Hershberger, Josh Faust
autogenerated on Mon Jan 6 2014 11:54:32