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 "ros/console.h"
00039 #include <boost/thread.hpp>
00040 #include <boost/shared_ptr.hpp>
00041 #include <boost/weak_ptr.hpp>
00042 #include <list>
00043 #include <actionlib/destruction_guard.h>
00044 
00045 namespace actionlib
00046 {
00047 
00053 template <class T>
00054 class ManagedList
00055 {
00056 private:
00057   struct TrackedElem
00058   {
00059     T elem;
00060     boost::weak_ptr<void> handle_tracker_;
00061   };
00062 
00063 public:
00064   class Handle;
00065 
00066   class iterator
00067   {
00068     public:
00069       iterator() { }
00070       T& operator*()  { return it_->elem; }
00071       T& operator->() { return it_->elem; }
00072       bool operator==(const iterator& rhs) const { return it_ == rhs.it_; }
00073       bool operator!=(const iterator& rhs) const { return !(*this == rhs); }
00074       void operator++() { it_++; }
00075       Handle createHandle();                   
00076       friend class ManagedList;
00077     private:
00078       iterator(typename std::list<TrackedElem>::iterator it) : it_(it) { }
00079       typename std::list<TrackedElem>::iterator it_;
00080   };
00081 
00082   typedef typename boost::function< void(iterator)> CustomDeleter;
00083 
00084 private:
00085   class ElemDeleter
00086   {
00087     public:
00088       ElemDeleter(iterator it, CustomDeleter deleter, const boost::shared_ptr<DestructionGuard>& guard) :
00089         it_(it), deleter_(deleter), guard_(guard)
00090       { }
00091 
00092       void operator() (void* ptr)
00093       {
00094         DestructionGuard::ScopedProtector protector(*guard_);
00095         if (!protector.isProtected())
00096         {
00097           ROS_ERROR_NAMED("actionlib", "ManagedList: The DestructionGuard associated with this list has already been destructed. You must delete all list handles before deleting the ManagedList");
00098           return;
00099         }
00100 
00101         ROS_DEBUG_NAMED("actionlib", "IN DELETER");
00102         if (deleter_)
00103           deleter_(it_);
00104       }
00105 
00106     private:
00107       iterator it_;
00108       CustomDeleter deleter_;
00109       boost::shared_ptr<DestructionGuard> guard_;
00110   };
00111 
00112 public:
00113 
00114   class Handle
00115   {
00116     public:
00120       Handle() : it_(iterator()), handle_tracker_(boost::shared_ptr<void>()), valid_(false) { }
00121 
00122       const Handle& operator=(const Handle& rhs)
00123       {
00124         if ( rhs.valid_ ) {
00125           it_ = rhs.it_;
00126         }
00127         handle_tracker_ = rhs.handle_tracker_;
00128         valid_ = rhs.valid_;
00129         return rhs;
00130       }
00131 
00136       void reset()
00137       {
00138         valid_ = false;
00139 #ifndef _MSC_VER
00140         // this prevents a crash on MSVC, but I bet the problem is elsewhere.
00141         // it puts the lotion in the basket.
00142         it_ = iterator();
00143 #endif
00144         handle_tracker_.reset();
00145       }
00146 
00152       T& getElem()
00153       {
00154         assert(valid_);
00155         return *it_;
00156       }
00157 
00161       bool operator==(const Handle& rhs)
00162       {
00163           assert(valid_);
00164           assert(rhs.valid_);
00165         return (it_ == rhs.it_);
00166       }
00167 
00168       friend class ManagedList;
00169       // Need this friend declaration so that iterator::createHandle() can
00170       // call the private Handle::Handle() declared below.
00171       friend class iterator;
00172     private:
00173       Handle( const boost::shared_ptr<void>& handle_tracker, iterator it) :
00174         it_(it), handle_tracker_(handle_tracker), valid_(true)
00175       { }
00176 
00177       iterator it_;
00178       boost::shared_ptr<void> handle_tracker_;
00179       bool valid_;
00180   };
00181 
00182   ManagedList() { }
00183 
00187   Handle add(const T& elem)
00188   {
00189     return add(elem, boost::bind(&ManagedList<T>::defaultDeleter, this, _1) );
00190   }
00191 
00197   Handle add(const T& elem, CustomDeleter custom_deleter, const boost::shared_ptr<DestructionGuard>& guard)
00198   {
00199     TrackedElem tracked_t;
00200     tracked_t.elem = elem;
00201 
00202     typename std::list<TrackedElem>::iterator list_it = list_.insert(list_.end(), tracked_t);
00203     iterator managed_it = iterator(list_it);
00204 
00205     ElemDeleter deleter(managed_it, custom_deleter, guard);
00206     boost::shared_ptr<void> tracker( (void*) NULL, deleter);
00207 
00208     list_it->handle_tracker_ = tracker;
00209 
00210     return Handle(tracker, managed_it);
00211   }
00212 
00216   void erase(iterator it)
00217   {
00218     list_.erase(it.it_);
00219   }
00220 
00221   iterator end()    { return iterator(list_.end()); }
00222   iterator begin()  { return iterator(list_.begin()); }
00223 
00224 private:
00225   void defaultDeleter(iterator it)
00226   {
00227     erase(it);
00228   }
00229   std::list<TrackedElem> list_;
00230 };
00231 
00232 
00233 template<class T>
00234 typename ManagedList<T>::Handle ManagedList<T>::iterator::createHandle()
00235 {
00236   if (it_->handle_tracker_.expired())
00237     ROS_ERROR_NAMED("actionlib", "Tried to create a handle to a list elem with refcount 0");
00238 
00239   boost::shared_ptr<void> tracker = it_->handle_tracker_.lock();
00240 
00241   return Handle(tracker, *this);
00242 }
00243 
00244 }
00245 
00246 #endif


actionlib
Author(s): Eitan Marder-Eppstein, Vijay Pradeep
autogenerated on Sun Oct 5 2014 22:02:55