Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Member Functions | Protected Member Functions | Friends | List of all members
nav2_costmap_2d::DenoiseLayer Class Reference

Layer filters noise-induced standalone obstacles (white costmap pixels) or small obstacles groups. More...

#include <nav2_costmap_2d/include/nav2_costmap_2d/denoise_layer.hpp>

Inheritance diagram for nav2_costmap_2d::DenoiseLayer:
Inheritance graph
[legend]
Collaboration diagram for nav2_costmap_2d::DenoiseLayer:
Collaboration graph
[legend]

Public Member Functions

void reset () override
 Reset this layer.
 
bool isClearable () override
 Reports that no clearing operation is required.
 
void updateBounds (double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y) override
 Reports that no expansion is required The method is called to ask the plugin: which area of costmap it needs to update. A layer is essentially a filter, so it never needs to expand bounds.
 
void updateCosts (nav2_costmap_2d::Costmap2D &master_grid, int min_x, int min_y, int max_x, int max_y) override
 Filters noise-induced obstacles in the selected region of the costmap The method is called when costmap recalculation is required. It updates the costmap within its window bounds. More...
 
- Public Member Functions inherited from nav2_costmap_2d::Layer
 Layer ()
 A constructor.
 
virtual ~Layer ()
 A destructor.
 
void initialize (LayeredCostmap *parent, std::string name, tf2_ros::Buffer *tf, const nav2_util::LifecycleNode::WeakPtr &node, rclcpp::CallbackGroup::SharedPtr callback_group)
 Initialization process of layer on startup.
 
virtual void deactivate ()
 Stop publishers.
 
virtual void activate ()
 Restart publishers if they've been stopped.
 
virtual void matchSize ()
 Implement this to make this layer match the size of the parent costmap.
 
virtual void onFootprintChanged ()
 LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint()). Override to be notified of changes to the robot's footprint.
 
std::string getName () const
 Get the name of the costmap layer.
 
bool isCurrent () const
 Check to make sure all the data in the layer is up to date. If the layer is not up to date, then it may be unsafe to plan using the data from this layer, and the planner may need to know. More...
 
bool isEnabled () const
 Gets whether the layer is enabled.
 
const std::vector< geometry_msgs::msg::Point > & getFootprint () const
 Convenience function for layered_costmap_->getFootprint().
 
void declareParameter (const std::string &param_name, const rclcpp::ParameterValue &value)
 Convenience functions for declaring ROS parameters.
 
void declareParameter (const std::string &param_name, const rclcpp::ParameterType &param_type)
 Convenience functions for declaring ROS parameters.
 
bool hasParameter (const std::string &param_name)
 Convenience functions for declaring ROS parameters.
 
std::string getFullName (const std::string &param_name)
 Convenience functions for declaring ROS parameters.
 

Protected Member Functions

void onInitialize () override
 Initializes the layer on startup This method is called at the end of plugin initialization. Reads plugin parameters from a config file.
 

Friends

class DenoiseLayerTester
 

Additional Inherited Members

- Protected Attributes inherited from nav2_costmap_2d::Layer
LayeredCostmaplayered_costmap_
 
std::string name_
 
tf2_ros::Buffer * tf_
 
rclcpp::CallbackGroup::SharedPtr callback_group_
 
rclcpp_lifecycle::LifecycleNode::WeakPtr node_
 
rclcpp::Clock::SharedPtr clock_
 
rclcpp::Logger logger_ {rclcpp::get_logger("nav2_costmap_2d")}
 
bool current_
 
bool enabled_
 
std::unordered_set< std::string > local_params_
 

Detailed Description

Layer filters noise-induced standalone obstacles (white costmap pixels) or small obstacles groups.

Definition at line 28 of file denoise_layer.hpp.

Member Function Documentation

◆ updateCosts()

void nav2_costmap_2d::DenoiseLayer::updateCosts ( nav2_costmap_2d::Costmap2D master_grid,
int  min_x,
int  min_y,
int  max_x,
int  max_y 
)
overridevirtual

Filters noise-induced obstacles in the selected region of the costmap The method is called when costmap recalculation is required. It updates the costmap within its window bounds.

Parameters
master_gridThe master costmap grid to update
min_xX min map coord of the window to update
min_yY min map coord of the window to update
max_xX max map coord of the window to update
max_yY max map coord of the window to update

Implements nav2_costmap_2d::Layer.

Definition at line 102 of file denoise_layer.cpp.

References nav2_costmap_2d::Costmap2D::getCharMap(), nav2_costmap_2d::Costmap2D::getDefaultValue(), and nav2_costmap_2d::Costmap2D::getSizeInCellsX().

Here is the call graph for this function:

The documentation for this class was generated from the following files: