Class CostmapDownsampler

Class Documentation

class CostmapDownsampler

A costmap downsampler for more efficient path planning.

Public Functions

CostmapDownsampler()

A constructor for CostmapDownsampler.

~CostmapDownsampler()

A destructor for CostmapDownsampler.

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.

Parameters:
  • node – Lifecycle node pointer

  • global_frame – The ID of the global frame used by the costmap

  • topic_name – The name of the topic to publish the downsampled costmap

  • costmap – The costmap we want to downsample

  • downsampling_factor – Multiplier for the costmap resolution

  • use_min_cost_neighbor – If true, min function is used instead of max for downsampling

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.

nav2_costmap_2d::Costmap2D *downsample(const unsigned int &downsampling_factor)

Downsample the given costmap by the downsampling factor, and publish the downsampled costmap.

Parameters:

downsampling_factor – Multiplier for the costmap resolution

Returns:

A ptr to the downsampled costmap

void resizeCostmap()

Resize the downsampled costmap. Used in case the costmap changes and we need to update the downsampled version.

Protected Functions

void updateCostmapSize()

Update the sizes X-Y of the costmap and its downsampled version.

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.

Parameters:
  • new_mx – The X-coordinate of the cell in the new costmap

  • new_my – The Y-coordinate of the cell in the new costmap

Protected Attributes

unsigned int _size_x
unsigned int _size_y
unsigned int _downsampled_size_x
unsigned int _downsampled_size_y
unsigned int _downsampling_factor
bool _use_min_cost_neighbor
float _downsampled_resolution
nav2_costmap_2d::Costmap2D *_costmap
std::unique_ptr<nav2_costmap_2d::Costmap2D> _downsampled_costmap
std::unique_ptr<nav2_costmap_2d::Costmap2DPublisher> _downsampled_costmap_pub