Nav2 Navigation Stack - humble
humble
ROS 2 Navigation Stack
|
A costmap downsampler for more efficient path planning. More...
#include <nav2_smac_planner/include/nav2_smac_planner/costmap_downsampler.hpp>
Public Member 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. More... | |
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. More... | |
void | resizeCostmap () |
Resize the downsampled costmap. Used in case the costmap changes and we need to update the downsampled version. | |
Protected Member 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. More... | |
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 |
A costmap downsampler for more efficient path planning.
Definition at line 32 of file costmap_downsampler.hpp.
nav2_costmap_2d::Costmap2D * nav2_smac_planner::CostmapDownsampler::downsample | ( | const unsigned int & | downsampling_factor | ) |
Downsample the given costmap by the downsampling factor, and publish the downsampled costmap.
downsampling_factor | Multiplier for the costmap resolution |
Definition at line 80 of file costmap_downsampler.cpp.
References resizeCostmap(), setCostOfCell(), and updateCostmapSize().
Referenced by nav2_smac_planner::NodeHybrid::resetObstacleHeuristic().
void nav2_smac_planner::CostmapDownsampler::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.
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 |
Definition at line 36 of file costmap_downsampler.cpp.
References nav2_costmap_2d::Costmap2D::getOriginX(), nav2_costmap_2d::Costmap2D::getOriginY(), and updateCostmapSize().
Referenced by nav2_smac_planner::NodeHybrid::resetObstacleHeuristic().
|
protected |
Explore all subcells of the original costmap and assign the max cost to the new (downsampled) cell.
new_mx | The X-coordinate of the cell in the new costmap |
new_my | The Y-coordinate of the cell in the new costmap |
Definition at line 126 of file costmap_downsampler.cpp.
References nav2_costmap_2d::Costmap2D::getCost().
Referenced by downsample().