15 #ifndef NAV2_SMAC_PLANNER__COSTMAP_DOWNSAMPLER_HPP_
16 #define NAV2_SMAC_PLANNER__COSTMAP_DOWNSAMPLER_HPP_
21 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
22 #include "nav2_smac_planner/constants.hpp"
24 namespace nav2_smac_planner
54 const nav2_util::LifecycleNode::WeakPtr & node,
55 const std::string & global_frame,
56 const std::string & topic_name,
58 const unsigned int & downsampling_factor,
59 const bool & use_min_cost_neighbor =
false);
100 const unsigned int & new_mx,
101 const unsigned int & new_my);
103 unsigned int _size_x;
104 unsigned int _size_y;
105 unsigned int _downsampled_size_x;
106 unsigned int _downsampled_size_y;
107 unsigned int _downsampling_factor;
108 bool _use_min_cost_neighbor;
109 float _downsampled_resolution;
111 std::unique_ptr<nav2_costmap_2d::Costmap2D> _downsampled_costmap;
112 std::unique_ptr<nav2_costmap_2d::Costmap2DPublisher> _downsampled_costmap_pub;
A 2D costmap provides a mapping between points in the world and their associated "costs".
A costmap downsampler for more efficient path planning.
~CostmapDownsampler()
A destructor for CostmapDownsampler.
CostmapDownsampler()
A constructor for CostmapDownsampler.
void resizeCostmap()
Resize the downsampled costmap. Used in case the costmap changes and we need to update the downsample...
void on_activate()
Activate the publisher of the downsampled costmap.
void on_deactivate()
Deactivate the publisher of the downsampled costmap.
void on_cleanup()
Cleanup the publisher of the downsampled costmap.
void updateCostmapSize()
Update the sizes X-Y of the costmap and its downsampled version.
void on_configure(const nav2_util::LifecycleNode::WeakPtr &node, const std::string &global_frame, const std::string &topic_name, nav2_costmap_2d::Costmap2D *const costmap, const unsigned int &downsampling_factor, const bool &use_min_cost_neighbor=false)
Configure the downsampled costmap object and the ROS publisher.
void setCostOfCell(const unsigned int &new_mx, const unsigned int &new_my)
Explore all subcells of the original costmap and assign the max cost to the new (downsampled) cell.
nav2_costmap_2d::Costmap2D * downsample(const unsigned int &downsampling_factor)
Downsample the given costmap by the downsampling factor, and publish the downsampled costmap.