Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
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>
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... | |
![]() | |
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 ¶m_name, const rclcpp::ParameterValue &value) |
Convenience functions for declaring ROS parameters. | |
void | declareParameter (const std::string ¶m_name, const rclcpp::ParameterType ¶m_type) |
Convenience functions for declaring ROS parameters. | |
bool | hasParameter (const std::string ¶m_name) |
Convenience functions for declaring ROS parameters. | |
std::string | getFullName (const std::string ¶m_name) |
Convenience functions for declaring ROS parameters. | |
std::string | joinWithParentNamespace (const std::string &topic) |
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 | |
![]() | |
LayeredCostmap * | layered_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_ |
Layer filters noise-induced standalone obstacles (white costmap pixels) or small obstacles groups.
Definition at line 28 of file denoise_layer.hpp.
|
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.
master_grid | The master costmap grid to update |
min_x | X min map coord of the window to update |
min_y | Y min map coord of the window to update |
max_x | X max map coord of the window to update |
max_y | Y 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().