00001 /* 00002 * Copyright (c) 2014-2017, the neonavigation authors 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 copyright holder 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 COSTMAP_CSPACE_POINTCLOUD_ACCUMULATOR_ACCUMULATOR_H 00031 #define COSTMAP_CSPACE_POINTCLOUD_ACCUMULATOR_ACCUMULATOR_H 00032 00033 #include <ros/ros.h> 00034 00035 #include <list> 00036 00037 template <typename T> 00038 class PointcloudAccumurator 00039 { 00040 public: 00041 class Points : public T 00042 { 00043 public: 00044 ros::Time stamp_; 00045 00046 Points(const T& points, const ros::Time& stamp) 00047 : T(points) 00048 , stamp_(stamp) 00049 { 00050 } 00051 }; 00052 00053 PointcloudAccumurator() 00054 { 00055 } 00056 00057 explicit PointcloudAccumurator(const ros::Duration& duration) 00058 { 00059 reset(duration); 00060 } 00061 00062 void reset(const ros::Duration& duration) 00063 { 00064 time_to_hold_ = duration; 00065 clear(); 00066 } 00067 00068 void clear() 00069 { 00070 points_.clear(); 00071 } 00072 00073 void push(const Points& points) 00074 { 00075 for (auto it = points_.begin(); it != points_.end(); ++it) 00076 { 00077 if (it->stamp_ + time_to_hold_ < points.stamp_) 00078 { 00079 it = points_.erase(it); 00080 continue; 00081 } 00082 break; 00083 } 00084 points_.push_back(points); 00085 } 00086 00087 typename std::list<Points>::iterator begin() 00088 { 00089 return points_.begin(); 00090 } 00091 typename std::list<Points>::iterator end() 00092 { 00093 return points_.end(); 00094 } 00095 00096 typename std::list<Points>::const_iterator begin() const 00097 { 00098 return points_.cbegin(); 00099 } 00100 typename std::list<Points>::const_iterator end() const 00101 { 00102 return points_.cend(); 00103 } 00104 00105 protected: 00106 ros::Duration time_to_hold_; 00107 std::list<Points> points_; 00108 }; 00109 00110 #endif // COSTMAP_CSPACE_POINTCLOUD_ACCUMULATOR_ACCUMULATOR_H