observation.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, 2013, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Authors: Conor McGann
30  */
31 
32 #ifndef COSTMAP_2D_OBSERVATION_H_
33 #define COSTMAP_2D_OBSERVATION_H_
34 
35 #include <geometry_msgs/Point.h>
36 #include <sensor_msgs/PointCloud2.h>
37 
38 namespace costmap_2d
39 {
40 
47 {
48 public:
53  cloud_(new sensor_msgs::PointCloud2()), obstacle_range_(0.0), raytrace_range_(0.0)
54  {
55  }
56 
57  virtual ~Observation()
58  {
59  delete cloud_;
60  }
61 
69  Observation(geometry_msgs::Point& origin, const sensor_msgs::PointCloud2 &cloud,
70  double obstacle_range, double raytrace_range) :
71  origin_(origin), cloud_(new sensor_msgs::PointCloud2(cloud)),
72  obstacle_range_(obstacle_range), raytrace_range_(raytrace_range)
73  {
74  }
75 
80  Observation(const Observation& obs) :
81  origin_(obs.origin_), cloud_(new sensor_msgs::PointCloud2(*(obs.cloud_))),
83  {
84  }
85 
91  Observation(const sensor_msgs::PointCloud2 &cloud, double obstacle_range) :
92  cloud_(new sensor_msgs::PointCloud2(cloud)), obstacle_range_(obstacle_range), raytrace_range_(0.0)
93  {
94  }
95 
96  geometry_msgs::Point origin_;
97  sensor_msgs::PointCloud2* cloud_;
99 };
100 
101 } // namespace costmap_2d
102 #endif // COSTMAP_2D_OBSERVATION_H_
geometry_msgs::Point origin_
Definition: observation.h:96
Observation(geometry_msgs::Point &origin, const sensor_msgs::PointCloud2 &cloud, double obstacle_range, double raytrace_range)
Creates an observation from an origin point and a point cloud.
Definition: observation.h:69
Observation(const sensor_msgs::PointCloud2 &cloud, double obstacle_range)
Creates an observation from a point cloud.
Definition: observation.h:91
Observation()
Creates an empty observation.
Definition: observation.h:52
Stores an observation in terms of a point cloud and the origin of the source.
Definition: observation.h:46
Observation(const Observation &obs)
Copy constructor.
Definition: observation.h:80
sensor_msgs::PointCloud2 * cloud_
Definition: observation.h:97


costmap_2d
Author(s): Eitan Marder-Eppstein, David V. Lu!!, Dave Hershberger, contradict@gmail.com
autogenerated on Wed Jun 22 2022 02:07:03