38 #ifndef NAV2_COSTMAP_2D__OBSTACLE_LAYER_HPP_
39 #define NAV2_COSTMAP_2D__OBSTACLE_LAYER_HPP_
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
52 #include "message_filters/subscriber.hpp"
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"
100 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
114 int min_i,
int min_j,
int max_i,
int max_j);
129 virtual void reset();
140 rcl_interfaces::msg::SetParametersResult
154 sensor_msgs::msg::LaserScan::ConstSharedPtr message,
155 const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer);
163 sensor_msgs::msg::LaserScan::ConstSharedPtr message,
164 const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer);
172 sensor_msgs::msg::PointCloud2::ConstSharedPtr message,
173 const std::shared_ptr<nav2_costmap_2d::ObservationBuffer> & buffer);
177 void clearStaticObservations(
bool marking,
bool clearing);
186 std::vector<nav2_costmap_2d::Observation> & marking_observations)
const;
194 std::vector<nav2_costmap_2d::Observation> & clearing_observations)
const;
206 double * min_x,
double * min_y,
214 double ox,
double oy,
double wx,
double wy,
double max_range,
double min_range,
215 double * min_x,
double * min_y,
219 std::vector<geometry_msgs::msg::Point> transformed_footprint_;
220 bool footprint_clearing_enabled_;
225 double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
237 std::vector<std::shared_ptr<message_filters::SubscriberBase<rclcpp_lifecycle::LifecycleNode>>>
252 std::vector<nav2_costmap_2d::Observation> static_clearing_observations_;
253 std::vector<nav2_costmap_2d::Observation> static_marking_observations_;
255 bool rolling_window_;
A 2D costmap provides a mapping between points in the world and their associated "costs".
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.
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.
ObstacleLayer()
A constructor.
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.