observation_buffer.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2008, Willow Garage, Inc.
00006 *  All rights reserved.
00007 *
00008 *  Redistribution and use in source and binary forms, with or without
00009 *  modification, are permitted provided that the following conditions
00010 *  are met:
00011 *
00012 *   * Redistributions of source code must retain the above copyright
00013 *     notice, this list of conditions and the following disclaimer.
00014 *   * Redistributions in binary form must reproduce the above
00015 *     copyright notice, this list of conditions and the following
00016 *     disclaimer in the documentation and/or other materials provided
00017 *     with the distribution.
00018 *   * Neither the name of the Willow Garage nor the names of its
00019 *     contributors may be used to endorse or promote products derived
00020 *     from this software without specific prior written permission.
00021 *
00022 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 *  POSSIBILITY OF SUCH DAMAGE.
00034 *
00035 * Author: Eitan Marder-Eppstein
00036 *********************************************************************/
00037 #ifndef COSTMAP_OBSERVATION_BUFFER_H_
00038 #define COSTMAP_OBSERVATION_BUFFER_H_
00039 
00040 #include <vector>
00041 #include <list>
00042 #include <string>
00043 #include <ros/time.h>
00044 #include <costmap_2d/observation.h>
00045 #include <tf/transform_listener.h>
00046 #include <tf/transform_datatypes.h>
00047 
00048 //PCL Stuff
00049 #include <pcl/point_types.h>
00050 #include <pcl/point_cloud.h>
00051 #include <pcl_ros/transforms.h>
00052 #include <pcl/ros/conversions.h>
00053 
00054 // Thread suppport
00055 #include <boost/thread.hpp>
00056 
00057 namespace costmap_2d {
00062   class ObservationBuffer {
00063     public:
00078       ObservationBuffer(std::string topic_name, double observation_keep_time, double expected_update_rate, 
00079           double min_obstacle_height, double max_obstacle_height, double obstacle_range, double raytrace_range,
00080           tf::TransformListener& tf, std::string global_frame, std::string sensor_frame, double tf_tolerance);
00081 
00085       ~ObservationBuffer();
00086 
00094       bool setGlobalFrame(const std::string new_global_frame);
00095 
00101       void bufferCloud(const sensor_msgs::PointCloud2& cloud);
00102 
00108       void bufferCloud(const pcl::PointCloud<pcl::PointXYZ>& cloud);
00109 
00114       void getObservations(std::vector<Observation>& observations);
00115 
00120       bool isCurrent() const;
00121 
00125       inline void lock() { lock_.lock(); }
00126 
00130       inline void unlock() { lock_.unlock(); }
00131       
00135       void resetLastUpdated ();
00136 
00137     private:
00141       void purgeStaleObservations();
00142 
00143       tf::TransformListener& tf_;
00144       const ros::Duration observation_keep_time_;
00145       const ros::Duration expected_update_rate_;
00146       ros::Time last_updated_;
00147       std::string global_frame_;
00148       std::string sensor_frame_;
00149       std::list<Observation> observation_list_;
00150       std::string topic_name_;
00151       double min_obstacle_height_, max_obstacle_height_;
00152       boost::recursive_mutex lock_; 
00153       double obstacle_range_, raytrace_range_;
00154       double tf_tolerance_;
00155   };
00156 };
00157 #endif


costmap_2d
Author(s): Eitan Marder-Eppstein
autogenerated on Sat Dec 28 2013 17:13:40