Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
obstacle_layer.hpp
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
38 #ifndef NAV2_COSTMAP_2D__OBSTACLE_LAYER_HPP_
39 #define NAV2_COSTMAP_2D__OBSTACLE_LAYER_HPP_
40 
41 #include <memory>
42 #include <string>
43 #include <vector>
44 
45 #include "rclcpp/rclcpp.hpp"
46 #include "rclcpp/version.h"
47 #include "laser_geometry/laser_geometry.hpp"
48 #pragma GCC diagnostic push
49 #pragma GCC diagnostic ignored "-Wreorder"
50 #include "tf2_ros/message_filter.hpp"
51 #pragma GCC diagnostic pop
52 
53 #include "message_filters/subscriber.hpp"
54 
55 #include "nav_msgs/msg/occupancy_grid.hpp"
56 #include "sensor_msgs/msg/laser_scan.hpp"
57 #include "sensor_msgs/msg/point_cloud.hpp"
58 #include "sensor_msgs/msg/point_cloud2.hpp"
59 #include "nav2_costmap_2d/costmap_layer.hpp"
60 #include "nav2_costmap_2d/layered_costmap.hpp"
61 #include "nav2_costmap_2d/observation_buffer.hpp"
62 #include "nav2_costmap_2d/footprint.hpp"
63 
64 namespace nav2_costmap_2d
65 {
66 
72 {
73 public:
78  {
79  costmap_ = NULL; // this is the unsigned char* member of parent class Costmap2D.
80  }
81 
85  virtual ~ObstacleLayer();
89  virtual void onInitialize();
100  virtual void updateBounds(
101  double robot_x, double robot_y, double robot_yaw, double * min_x,
102  double * min_y,
103  double * max_x,
104  double * max_y);
113  virtual void updateCosts(
114  nav2_costmap_2d::Costmap2D & master_grid,
115  int min_i, int min_j, int max_i, int max_j);
116 
120  virtual void deactivate();
121 
125  virtual void activate();
126 
130  virtual void reset();
131 
135  virtual bool isClearable() {return true;}
136 
141  rcl_interfaces::msg::SetParametersResult
142  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
143 
148 
154  void laserScanCallback(
155  sensor_msgs::msg::LaserScan::ConstSharedPtr message,
156  const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer);
157 
164  sensor_msgs::msg::LaserScan::ConstSharedPtr message,
165  const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer);
166 
172  void pointCloud2Callback(
173  sensor_msgs::msg::PointCloud2::ConstSharedPtr message,
174  const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer);
175 
176  // for testing purposes
177  void addStaticObservation(nav2_costmap_2d::Observation & obs, bool marking, bool clearing);
178  void clearStaticObservations(bool marking, bool clearing);
179 
180 protected:
187  std::vector<nav2_costmap_2d::Observation> & marking_observations) const;
188 
195  std::vector<nav2_costmap_2d::Observation> & clearing_observations) const;
196 
205  virtual void raytraceFreespace(
206  const nav2_costmap_2d::Observation & clearing_observation,
207  double * min_x, double * min_y,
208  double * max_x,
209  double * max_y);
210 
215  double ox, double oy, double wx, double wy, double max_range, double min_range,
216  double * min_x, double * min_y,
217  double * max_x,
218  double * max_y);
219 
220  std::vector<geometry_msgs::msg::Point> transformed_footprint_;
221  bool footprint_clearing_enabled_;
225  void updateFootprint(
226  double robot_x, double robot_y, double robot_yaw, double * min_x,
227  double * min_y,
228  double * max_x,
229  double * max_y);
230 
231  std::string global_frame_;
234 
236  laser_geometry::LaserProjection projector_;
238  #if RCLCPP_VERSION_GTE(29, 6, 0)
239  std::vector<std::shared_ptr<message_filters::SubscriberBase>>
241  #else
242  std::vector<std::shared_ptr<message_filters::SubscriberBase<rclcpp_lifecycle::LifecycleNode>>>
244  #endif
246  std::vector<std::shared_ptr<tf2_ros::MessageFilterBase>> observation_notifiers_;
248  std::vector<std::shared_ptr<nav2_costmap_2d::ObservationBuffer>> observation_buffers_;
250  std::vector<std::shared_ptr<nav2_costmap_2d::ObservationBuffer>> marking_buffers_;
252  std::vector<std::shared_ptr<nav2_costmap_2d::ObservationBuffer>> clearing_buffers_;
253 
255  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
256 
257  // Used only for testing purposes
258  std::vector<nav2_costmap_2d::Observation> static_clearing_observations_;
259  std::vector<nav2_costmap_2d::Observation> static_marking_observations_;
260 
261  bool rolling_window_;
262  bool was_reset_;
263  nav2_costmap_2d::CombinationMethod combination_method_;
264 };
265 
266 } // namespace nav2_costmap_2d
267 
268 #endif // NAV2_COSTMAP_2D__OBSTACLE_LAYER_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
A costmap layer base class for costmap plugin layers. Rather than just a layer, this object also cont...
Stores an observation in terms of a point cloud and the origin of the source.
Definition: observation.hpp:47
Takes in laser and pointcloud data to populate into 2D costmap.
void pointCloud2Callback(sensor_msgs::msg::PointCloud2::ConstSharedPtr message, const std::shared_ptr< nav2_costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering PointCloud2 messages.
virtual bool isClearable()
If clearing operations should be processed on this layer or not.
std::vector< std::shared_ptr< nav2_costmap_2d::ObservationBuffer > > marking_buffers_
Used to store observation buffers used for marking obstacles.
virtual void activate()
Activate the layer.
std::vector< std::shared_ptr< tf2_ros::MessageFilterBase > > observation_notifiers_
Used to make sure that transforms are available for each sensor.
bool getMarkingObservations(std::vector< nav2_costmap_2d::Observation > &marking_observations) const
Get the observations used to mark space.
std::string global_frame_
The global frame for the costmap.
bool getClearingObservations(std::vector< nav2_costmap_2d::Observation > &clearing_observations) const
Get the observations used to clear space.
void updateRaytraceBounds(double ox, double oy, double wx, double wy, double max_range, double min_range, double *min_x, double *min_y, double *max_x, double *max_y)
Process update costmap with raytracing the window bounds.
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_
Dynamic parameters handler.
void laserScanCallback(sensor_msgs::msg::LaserScan::ConstSharedPtr message, const std::shared_ptr< nav2_costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering LaserScan messages.
void resetBuffersLastUpdated()
triggers the update of observations buffer
std::vector< std::shared_ptr< nav2_costmap_2d::ObservationBuffer > > clearing_buffers_
Used to store observation buffers used for clearing obstacles.
void laserScanValidInfCallback(sensor_msgs::msg::LaserScan::ConstSharedPtr message, const std::shared_ptr< nav2_costmap_2d::ObservationBuffer > &buffer)
A callback to handle buffering LaserScan messages which need filtering to turn Inf values into range_...
std::vector< std::shared_ptr< message_filters::SubscriberBase< rclcpp_lifecycle::LifecycleNode > > > observation_subscribers_
Used for the observation message filters.
void updateFootprint(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Clear costmap layer info below the robot's footprint.
virtual void deactivate()
Deactivate the layer.
virtual void updateCosts(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Update the costs in the master costmap in the window.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
virtual ~ObstacleLayer()
A destructor.
std::vector< std::shared_ptr< nav2_costmap_2d::ObservationBuffer > > observation_buffers_
Used to store observations from various sensors.
virtual void onInitialize()
Initialization process of layer on startup.
double min_obstacle_height_
Max Obstacle Height.
laser_geometry::LaserProjection projector_
Used to project laser scans into point clouds.
double max_obstacle_height_
Max Obstacle Height.
virtual void reset()
Reset this costmap.
virtual void raytraceFreespace(const nav2_costmap_2d::Observation &clearing_observation, double *min_x, double *min_y, double *max_x, double *max_y)
Clear freespace based on one observation.
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Update the bounds of the master costmap by this layer's update dimensions.