property_node.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2010, 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 #ifndef RVE_PROPERTIES_PROPERTY_NODE_H
00031 #define RVE_PROPERTIES_PROPERTY_NODE_H
00032 
00033 #include "forwards.h"
00034 #include "property_value.h"
00035 
00036 #include <string>
00037 #include <map>
00038 #include <vector>
00039 
00040 #include <ros/types.h>
00041 #include <ros/assert.h>
00042 
00043 #include <stdexcept>
00044 
00045 #include <boost/thread/recursive_mutex.hpp>
00046 #include <boost/shared_ptr.hpp>
00047 #include <boost/enable_shared_from_this.hpp>
00048 #include <boost/function.hpp>
00049 
00050 namespace ros
00051 {
00052 class CallbackQueueInterface;
00053 }
00054 
00055 namespace rve_properties
00056 {
00057 
00058 class BadPathException : public std::runtime_error
00059 {
00060 public:
00061   BadPathException(const std::string& error)
00062   : std::runtime_error(error)
00063   {}
00064 };
00065 
00066 struct PropertyData
00067 {
00068   PropertyData()
00069   : metadata(0)
00070   {}
00071 
00072   PropertyValue value;
00073   std::map<std::string, std::string>* metadata;         // Only allocate if necessary
00074 };
00075 
00076 class PropertyNode;
00077 typedef boost::shared_ptr<PropertyNode> PropertyNodePtr;
00078 typedef std::vector<PropertyNodePtr> V_PropertyNode;
00079 
00080 typedef boost::function<void(const PropertyNodePtr&, const std::string&, PropertyChangeType)> PropertyChangeCallback;
00081 
00082 class PropertyNode : public boost::enable_shared_from_this<PropertyNode>
00083 {
00084 public:
00085   PropertyNode();
00086   ~PropertyNode();
00087 
00088   PropertyNodePtr getNode(const std::string& path, bool create_if_necessary = true);
00089   void setNode(const std::string& path, const PropertyNodePtr& node);
00090   void removeNode(const std::string& path);
00091   bool exists(const std::string& path);
00092   bool hasValue();
00093 
00094   template<typename T>
00095   void set(T t)
00096   {
00097     {
00098       boost::recursive_mutex::scoped_lock lock(mutex_);
00099       data_.value.set(t);
00100     }
00101 
00102     fireChanged(shared_from_this(), "", PropertyChanged);
00103   }
00104 
00105   template<typename T>
00106   T get()
00107   {
00108     boost::recursive_mutex::scoped_lock lock(mutex_);
00109     return data_.value.get<T>();
00110   }
00111 
00112   template<typename T>
00113   void get(T& t)
00114   {
00115     boost::recursive_mutex::scoped_lock lock(mutex_);
00116     data_.value.get(t);
00117   }
00118 
00119   template<typename T>
00120   void get(T& t, T default_value)
00121   {
00122     boost::recursive_mutex::scoped_lock lock(mutex_);
00123     data_.value.get(t, default_value);
00124   }
00125 
00126   template<typename T>
00127   void set(const std::string& path, T t)
00128   {
00129     PropertyNodePtr n = getNode(path);
00130     n->set(t);
00131   }
00132 
00133   template<typename T>
00134   T get(const std::string& path)
00135   {
00136     PropertyNodePtr n = getNode(path);
00137     return n->get<T>();
00138   }
00139 
00140   template<typename T>
00141   void get(const std::string& path, T& t)
00142   {
00143     PropertyNodePtr n = getNode(path);
00144     n->get(t);
00145   }
00146 
00147   template<typename T>
00148   void get(const std::string& path, T& t, T default_value)
00149   {
00150     PropertyNodePtr n = getNode(path);
00151     n->get(t, default_value);
00152   }
00153 
00154   void addChangeCallback(const PropertyChangeCallback& cb, void* owner, ros::CallbackQueueInterface* callback_queue);
00155   void removeChangeCallback(void* owner);
00156 
00157   PropertyNodePtr getParent();
00158 
00159   PropertyValue getValue() { return data_.value; }
00160   std::string getName() { return name_; }
00161 
00162   template<typename F>
00163   void visitChildren(F& f, bool recurse = true, const std::string& base_path = std::string())
00164   {
00165     boost::recursive_mutex::scoped_lock lock(mutex_);
00166     if (!children_)
00167     {
00168       return;
00169     }
00170 
00171     std::string new_base;
00172     if (name_.empty())
00173     {
00174       ROS_ASSERT(!parent_);
00175       new_base = base_path;
00176     }
00177     else
00178     {
00179       if (base_path.empty())
00180       {
00181         new_base = name_;
00182       }
00183       else
00184       {
00185         new_base = base_path + "/" + name_;
00186       }
00187     }
00188 
00189     M_PropertyNode::iterator it = children_->begin();
00190     M_PropertyNode::iterator end = children_->end();
00191     for (; it != end; ++it)
00192     {
00193       const PropertyNodePtr& child = it->second;
00194       std::string full_child_path = new_base.empty() ? it->first : new_base + "/" + it->first;
00195       f(full_child_path, child);
00196       if (recurse)
00197       {
00198         child->visitChildren(f, recurse, new_base);
00199       }
00200     }
00201   }
00202 
00203   void getChildren(V_PropertyNode& out_children)
00204   {
00205     out_children.clear();
00206 
00207     boost::recursive_mutex::scoped_lock lock(mutex_);
00208     if (!children_)
00209     {
00210       return;
00211     }
00212 
00213     out_children.reserve(children_->size());
00214 
00215     M_PropertyNode::iterator it = children_->begin();
00216     M_PropertyNode::iterator end = children_->end();
00217     for (; it != end; ++it)
00218     {
00219       const PropertyNodePtr& child = it->second;
00220       out_children.push_back(child);
00221     }
00222   }
00223 
00224 private:
00225   PropertyNode(const PropertyNode&);
00226   PropertyNode& operator=(const PropertyNode&);
00227 
00228   std::pair<PropertyNodePtr, std::string> getParentOf(const std::string& path);
00229 
00230   void setChild(const std::string& name, const PropertyNodePtr& node);
00231   void childChanged(const PropertyNodePtr& child, const std::string& child_path, PropertyChangeType type);
00232   void fireChanged(const PropertyNodePtr& node, const std::string& path, PropertyChangeType type);
00233 
00234   void setParent(PropertyNode* parent, const std::string& name, bool remove_from_previous);
00235 
00236   boost::recursive_mutex mutex_;  // TODO do we want to remove exposure of boost/thread/recursive_mutex.hpp from this header?
00237   PropertyData data_;
00238 
00239   std::string name_;
00240   PropertyNode* parent_;
00241 
00242   typedef std::map<std::string, PropertyNodePtr> M_PropertyNode;
00243   M_PropertyNode* children_;  // Only allocate if necessary
00244 
00245   struct ChangeCallback
00246   {
00247     PropertyChangeCallback cb;
00248     void* owner;
00249     ros::CallbackQueueInterface* queue;
00250   };
00251   typedef std::vector<ChangeCallback> V_ChangeCallback;
00252   V_ChangeCallback* change_callbacks_;  // Only allocate if necessary
00253 };
00254 
00255 }
00256 
00257 #endif // RVE_PROPERTIES_PROPERTY_NODE_H


rve_properties
Author(s): Josh Faust
autogenerated on Wed Dec 11 2013 14:31:27