managed_list.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2008, Willow Garage, Inc.
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 Willow Garage 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 #ifndef ACTIONLIB__MANAGED_LIST_H_
00036 #define ACTIONLIB__MANAGED_LIST_H_
00037 
00038 #include <actionlib/destruction_guard.h>
00039 #include <boost/thread.hpp>
00040 #include <boost/shared_ptr.hpp>
00041 #include <boost/weak_ptr.hpp>
00042 
00043 #include <list>
00044 
00045 #include "ros/console.h"
00046 
00047 namespace actionlib
00048 {
00049 
00055 template<class T>
00056 class ManagedList
00057 {
00058 private:
00059   struct TrackedElem
00060   {
00061     T elem;
00062     boost::weak_ptr<void> handle_tracker_;
00063   };
00064 
00065 public:
00066   class Handle;
00067 
00068   class iterator
00069   {
00070 public:
00071     iterator() {}
00072     T & operator*() {return it_->elem; }
00073     T & operator->() {return it_->elem; }
00074     const T & operator*()  const {return it_->elem; }
00075     const T & operator->() const {return it_->elem; }
00076     bool operator==(const iterator & rhs) const {return it_ == rhs.it_; }
00077     bool operator!=(const iterator & rhs) const {return !(*this == rhs); }
00078     void operator++() {it_++; }
00079     Handle createHandle();    
00080     friend class ManagedList;
00081 
00082 private:
00083     iterator(typename std::list<TrackedElem>::iterator it)
00084     : it_(it) {}
00085     typename std::list<TrackedElem>::iterator it_;
00086   };
00087 
00088   typedef typename boost::function<void (iterator)> CustomDeleter;
00089 
00090 private:
00091   class ElemDeleter
00092   {
00093 public:
00094     ElemDeleter(iterator it, CustomDeleter deleter,
00095       const boost::shared_ptr<DestructionGuard> & guard)
00096     : it_(it), deleter_(deleter), guard_(guard)
00097     {}
00098 
00099     void operator()(void *)
00100     {
00101       DestructionGuard::ScopedProtector protector(*guard_);
00102       if (!protector.isProtected()) {
00103         ROS_ERROR_NAMED("actionlib",
00104           "ManagedList: The DestructionGuard associated with this list has already been destructed. You must delete all list handles before deleting the ManagedList");
00105         return;
00106       }
00107 
00108       ROS_DEBUG_NAMED("actionlib", "IN DELETER");
00109       if (deleter_) {
00110         deleter_(it_);
00111       }
00112     }
00113 
00114 private:
00115     iterator it_;
00116     CustomDeleter deleter_;
00117     boost::shared_ptr<DestructionGuard> guard_;
00118   };
00119 
00120 public:
00121   class Handle
00122   {
00123 public:
00127     Handle()
00128     : it_(iterator()), handle_tracker_(boost::shared_ptr<void>()), valid_(false) {}
00129 
00130     Handle & operator=(const Handle & rhs)
00131     {
00132       if (rhs.valid_) {
00133         it_ = rhs.it_;
00134       }
00135       handle_tracker_ = rhs.handle_tracker_;
00136       valid_ = rhs.valid_;
00137       return *this;
00138     }
00139 
00144     void reset()
00145     {
00146       valid_ = false;
00147 #ifndef _MSC_VER
00148       // this prevents a crash on MSVC, but I bet the problem is elsewhere.
00149       // it puts the lotion in the basket.
00150       it_ = iterator();
00151 #endif
00152       handle_tracker_.reset();
00153     }
00154 
00160     T & getElem()
00161     {
00162       assert(valid_);
00163       if (!valid_) {
00164         ROS_ERROR_NAMED("actionlib","getElem() should not see invalid handles");
00165       }
00166       return *it_;
00167     }
00168 
00169     const T & getElem() const
00170     {
00171       assert(valid_);
00172       if (!valid_) {
00173         ROS_ERROR_NAMED("actionlib","getElem() should not see invalid handles");
00174       }
00175       return *it_;
00176     }
00177 
00181     bool operator==(const Handle & rhs) const
00182     {
00183       assert(valid_);
00184       if (!valid_) {
00185         ROS_ERROR_NAMED("actionlib", "operator== should not see invalid handles");
00186       }
00187       assert(rhs.valid_);
00188       if (!rhs.valid_) {
00189         ROS_ERROR_NAMED("actionlib", "operator== should not see invalid RHS handles");
00190       }
00191       return it_ == rhs.it_;
00192     }
00193 
00194     friend class ManagedList;
00195     // Need this friend declaration so that iterator::createHandle() can
00196     // call the private Handle::Handle() declared below.
00197     friend class iterator;
00198 
00199 private:
00200     Handle(const boost::shared_ptr<void> & handle_tracker, iterator it)
00201     : it_(it), handle_tracker_(handle_tracker), valid_(true)
00202     {}
00203 
00204     iterator it_;
00205     boost::shared_ptr<void> handle_tracker_;
00206     bool valid_;
00207   };
00208 
00209   ManagedList() {}
00210 
00214   Handle add(const T & elem)
00215   {
00216     return add(elem, boost::bind(&ManagedList<T>::defaultDeleter, this, _1) );
00217   }
00218 
00224   Handle add(const T & elem, CustomDeleter custom_deleter,
00225     const boost::shared_ptr<DestructionGuard> & guard)
00226   {
00227     TrackedElem tracked_t;
00228     tracked_t.elem = elem;
00229 
00230     typename std::list<TrackedElem>::iterator list_it = list_.insert(list_.end(), tracked_t);
00231     iterator managed_it = iterator(list_it);
00232 
00233     ElemDeleter deleter(managed_it, custom_deleter, guard);
00234     boost::shared_ptr<void> tracker( (void *) NULL, deleter);
00235 
00236     list_it->handle_tracker_ = tracker;
00237 
00238     return Handle(tracker, managed_it);
00239   }
00240 
00244   void erase(iterator it)
00245   {
00246     list_.erase(it.it_);
00247   }
00248 
00249   iterator end() {return iterator(list_.end()); }
00250   iterator begin() {return iterator(list_.begin()); }
00251 
00252 private:
00253   void defaultDeleter(iterator it)
00254   {
00255     erase(it);
00256   }
00257   std::list<TrackedElem> list_;
00258 };
00259 
00260 
00261 template<class T>
00262 typename ManagedList<T>::Handle ManagedList<T>::iterator::createHandle() {
00263   if (it_->handle_tracker_.expired()) {
00264     ROS_ERROR_NAMED("actionlib", "Tried to create a handle to a list elem with refcount 0");
00265   }
00266 
00267   boost::shared_ptr<void> tracker = it_->handle_tracker_.lock();
00268 
00269   return Handle(tracker, *this);
00270 }
00271 
00272 }  // namespace actionlib
00273 
00274 #endif  // ACTIONLIB__MANAGED_LIST_H_


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep, Mikael Arguedas
autogenerated on Sat Feb 16 2019 03:21:28