Nav2 Navigation Stack - kilted  kilted
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 "laser_geometry/laser_geometry.hpp"
47 #pragma GCC diagnostic push
48 #pragma GCC diagnostic ignored "-Wreorder"
49 #include "tf2_ros/message_filter.h"
50 #pragma GCC diagnostic pop
51 
52 #include "message_filters/subscriber.hpp"
53 
54 #include "nav_msgs/msg/occupancy_grid.hpp"
55 #include "sensor_msgs/msg/laser_scan.hpp"
56 #include "sensor_msgs/msg/point_cloud.hpp"
57 #include "sensor_msgs/msg/point_cloud2.hpp"
58 #include "nav2_costmap_2d/costmap_layer.hpp"
59 #include "nav2_costmap_2d/layered_costmap.hpp"
60 #include "nav2_costmap_2d/observation_buffer.hpp"
61 #include "nav2_costmap_2d/footprint.hpp"
62 
63 namespace nav2_costmap_2d
64 {
65 
71 {
72 public:
77  {
78  costmap_ = NULL; // this is the unsigned char* member of parent class Costmap2D.
79  }
80 
84  virtual ~ObstacleLayer();
88  virtual void onInitialize();
99  virtual void updateBounds(
100  double robot_x, double robot_y, double robot_yaw, double * min_x,
101  double * min_y,
102  double * max_x,
103  double * max_y);
112  virtual void updateCosts(
113  nav2_costmap_2d::Costmap2D & master_grid,
114  int min_i, int min_j, int max_i, int max_j);
115 
119  virtual void deactivate();
120 
124  virtual void activate();
125 
129  virtual void reset();
130 
134  virtual bool isClearable() {return true;}
135 
140  rcl_interfaces::msg::SetParametersResult
141  dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
142 
147 
153  void laserScanCallback(
154  sensor_msgs::msg::LaserScan::ConstSharedPtr message,
155  const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer);
156 
163  sensor_msgs::msg::LaserScan::ConstSharedPtr message,
164  const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer);
165 
171  void pointCloud2Callback(
172  sensor_msgs::msg::PointCloud2::ConstSharedPtr message,
173  const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer);
174 
175  // for testing purposes
176  void addStaticObservation(nav2_costmap_2d::Observation & obs, bool marking, bool clearing);
177  void clearStaticObservations(bool marking, bool clearing);
178 
179 protected:
186  std::vector<nav2_costmap_2d::Observation> & marking_observations) const;
187 
194  std::vector<nav2_costmap_2d::Observation> & clearing_observations) const;
195 
204  virtual void raytraceFreespace(
205  const nav2_costmap_2d::Observation & clearing_observation,
206  double * min_x, double * min_y,
207  double * max_x,
208  double * max_y);
209 
214  double ox, double oy, double wx, double wy, double max_range, double min_range,
215  double * min_x, double * min_y,
216  double * max_x,
217  double * max_y);
218 
219  std::vector<geometry_msgs::msg::Point> transformed_footprint_;
220  bool footprint_clearing_enabled_;
224  void updateFootprint(
225  double robot_x, double robot_y, double robot_yaw, double * min_x,
226  double * min_y,
227  double * max_x,
228  double * max_y);
229 
230  std::string global_frame_;
233 
235  laser_geometry::LaserProjection projector_;
237  std::vector<std::shared_ptr<message_filters::SubscriberBase<rclcpp_lifecycle::LifecycleNode>>>
240  std::vector<std::shared_ptr<tf2_ros::MessageFilterBase>> observation_notifiers_;
242  std::vector<std::shared_ptr<nav2_costmap_2d::ObservationBuffer>> observation_buffers_;
244  std::vector<std::shared_ptr<nav2_costmap_2d::ObservationBuffer>> marking_buffers_;
246  std::vector<std::shared_ptr<nav2_costmap_2d::ObservationBuffer>> clearing_buffers_;
247 
249  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr dyn_params_handler_;
250 
251  // Used only for testing purposes
252  std::vector<nav2_costmap_2d::Observation> static_clearing_observations_;
253  std::vector<nav2_costmap_2d::Observation> static_marking_observations_;
254 
255  bool rolling_window_;
256  bool was_reset_;
257  nav2_costmap_2d::CombinationMethod combination_method_;
258 };
259 
260 } // namespace nav2_costmap_2d
261 
262 #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.