Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
observation.hpp
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 NAV2_COSTMAP_2D__OBSERVATION_HPP_
33 #define NAV2_COSTMAP_2D__OBSERVATION_HPP_
34 
35 #include <geometry_msgs/msg/point.hpp>
36 #include <sensor_msgs/msg/point_cloud2.hpp>
37 
38 namespace nav2_costmap_2d
39 {
40 
47 {
48 public:
53  : cloud_(new sensor_msgs::msg::PointCloud2()), obstacle_max_range_(0.0), obstacle_min_range_(0.0),
54  raytrace_max_range_(0.0),
55  raytrace_min_range_(0.0)
56  {
57  }
61  virtual ~Observation()
62  {
63  delete cloud_;
64  }
65 
71  {
72  origin_ = obs.origin_;
73  cloud_ = new sensor_msgs::msg::PointCloud2(*(obs.cloud_));
74  obstacle_max_range_ = obs.obstacle_max_range_;
75  obstacle_min_range_ = obs.obstacle_min_range_;
76  raytrace_max_range_ = obs.raytrace_max_range_;
77  raytrace_min_range_ = obs.raytrace_min_range_;
78 
79  return *this;
80  }
81 
92  geometry_msgs::msg::Point & origin, const sensor_msgs::msg::PointCloud2 & cloud,
93  double obstacle_max_range, double obstacle_min_range, double raytrace_max_range,
94  double raytrace_min_range)
95  : origin_(origin), cloud_(new sensor_msgs::msg::PointCloud2(cloud)),
96  obstacle_max_range_(obstacle_max_range), obstacle_min_range_(obstacle_min_range),
97  raytrace_max_range_(raytrace_max_range), raytrace_min_range_(
98  raytrace_min_range)
99  {
100  }
101 
107  : origin_(obs.origin_), cloud_(new sensor_msgs::msg::PointCloud2(*(obs.cloud_))),
108  obstacle_max_range_(obs.obstacle_max_range_), obstacle_min_range_(obs.obstacle_min_range_),
109  raytrace_max_range_(obs.raytrace_max_range_),
110  raytrace_min_range_(obs.raytrace_min_range_)
111  {
112  }
113 
121  const sensor_msgs::msg::PointCloud2 & cloud, double obstacle_max_range,
122  double obstacle_min_range)
123  : cloud_(new sensor_msgs::msg::PointCloud2(cloud)), obstacle_max_range_(obstacle_max_range),
124  obstacle_min_range_(obstacle_min_range),
125  raytrace_max_range_(0.0), raytrace_min_range_(0.0)
126  {
127  }
128 
129  geometry_msgs::msg::Point origin_;
130  sensor_msgs::msg::PointCloud2 * cloud_;
131  double obstacle_max_range_, obstacle_min_range_, raytrace_max_range_, raytrace_min_range_;
132 };
133 
134 } // namespace nav2_costmap_2d
135 #endif // NAV2_COSTMAP_2D__OBSERVATION_HPP_
Stores an observation in terms of a point cloud and the origin of the source.
Definition: observation.hpp:47
Observation & operator=(const Observation &obs)
Copy assignment operator.
Definition: observation.hpp:70
Observation(geometry_msgs::msg::Point &origin, const sensor_msgs::msg::PointCloud2 &cloud, double obstacle_max_range, double obstacle_min_range, double raytrace_max_range, double raytrace_min_range)
Creates an observation from an origin point and a point cloud.
Definition: observation.hpp:91
virtual ~Observation()
A destructor.
Definition: observation.hpp:61
Observation(const sensor_msgs::msg::PointCloud2 &cloud, double obstacle_max_range, double obstacle_min_range)
Creates an observation from a point cloud.
Observation(const Observation &obs)
Copy constructor.
Observation()
Creates an empty observation.
Definition: observation.hpp:52