observation.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, 2013, 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  * Authors: Conor McGann
00030  */
00031 
00032 #ifndef COSTMAP_OBSERVATION_H_
00033 #define COSTMAP_OBSERVATION_H_
00034 
00035 #include <geometry_msgs/Point.h>
00036 #include <pcl/point_types.h>
00037 #include <pcl/point_cloud.h>
00038 
00039 namespace costmap_2d
00040 {
00041 
00047 class Observation
00048 {
00049 public:
00053   Observation() :
00054     cloud_(new pcl::PointCloud<pcl::PointXYZ>()), obstacle_range_(0.0), raytrace_range_(0.0)
00055   {
00056   }
00057 
00058   virtual ~Observation()
00059   {
00060     delete cloud_;
00061   }
00062 
00070   Observation(geometry_msgs::Point& origin, pcl::PointCloud<pcl::PointXYZ> cloud, double obstacle_range,
00071               double raytrace_range) :
00072       origin_(origin), cloud_(new pcl::PointCloud<pcl::PointXYZ>(cloud)), obstacle_range_(obstacle_range), raytrace_range_(raytrace_range)
00073   {
00074   }
00075 
00080   Observation(const Observation& obs) :
00081       origin_(obs.origin_), cloud_(new pcl::PointCloud<pcl::PointXYZ>(*(obs.cloud_))), obstacle_range_(obs.obstacle_range_), raytrace_range_(
00082           obs.raytrace_range_)
00083   {
00084   }
00085 
00091   Observation(pcl::PointCloud<pcl::PointXYZ> cloud, double obstacle_range) :
00092       cloud_(new pcl::PointCloud<pcl::PointXYZ>(cloud)), obstacle_range_(obstacle_range), raytrace_range_(0.0)
00093   {
00094   }
00095 
00096   geometry_msgs::Point origin_;
00097   pcl::PointCloud<pcl::PointXYZ>* cloud_;
00098   double obstacle_range_, raytrace_range_;
00099 };
00100 
00101 }
00102 #endif


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Thu Aug 27 2015 14:06:55