32 #ifndef NAV2_COSTMAP_2D__OBSERVATION_HPP_
33 #define NAV2_COSTMAP_2D__OBSERVATION_HPP_
35 #include <geometry_msgs/msg/point.hpp>
36 #include <sensor_msgs/msg/point_cloud2.hpp>
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)
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_;
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_(
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_)
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)
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_;
Stores an observation in terms of a point cloud and the origin of the source.
Observation & operator=(const Observation &obs)
Copy assignment operator.
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.
virtual ~Observation()
A destructor.
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.