15 #ifndef NAV2_COSTMAP_2D__PLUGIN_CONTAINER_LAYER_HPP_
16 #define NAV2_COSTMAP_2D__PLUGIN_CONTAINER_LAYER_HPP_
18 #include <Eigen/Dense>
24 #include "rclcpp/rclcpp.hpp"
25 #include "nav2_costmap_2d/layer.hpp"
26 #include "nav2_costmap_2d/layered_costmap.hpp"
27 #include "nav2_costmap_2d/costmap_layer.hpp"
28 #include "nav2_costmap_2d/observation_buffer.hpp"
29 #include "nav2_costmap_2d/inflation_layer.hpp"
30 #include "tf2_ros/message_filter.h"
31 #include "pluginlib/class_loader.hpp"
33 using nav2_costmap_2d::LETHAL_OBSTACLE;
34 using nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE;
35 using nav2_costmap_2d::NO_INFORMATION;
36 using rcl_interfaces::msg::ParameterType;
106 void clearArea(
int start_x,
int start_y,
int end_x,
int end_y,
bool invert)
override;
108 void addPlugin(std::shared_ptr<Layer> plugin, std::string layer_name);
109 pluginlib::ClassLoader<Layer> plugin_loader_{
"nav2_costmap_2d",
"nav2_costmap_2d::Layer"};
115 std::vector<rclcpp::Parameter> parameters);
119 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
123 std::vector<std::shared_ptr<Layer>> plugins_;
124 std::vector<std::string> plugin_names_;
125 std::vector<std::string> plugin_types_;
A 2D costmap provides a mapping between points in the world and their associated "costs".
A costmap layer base class for costmap plugin layers. Rather than just a layer, this object also cont...
Holds a list of plugins and applies them only to the specific layer.
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(std::vector< rclcpp::Parameter > parameters)
Callback executed when a parameter change is detected.
virtual void onInitialize()
Initialization process of layer on startup.
virtual void matchSize()
Update the footprint to match size of the parent costmap.
virtual void onFootprintChanged()
LayeredCostmap calls this whenever the footprint there changes (via LayeredCostmap::setFootprint())....
virtual void updateBounds(double robot_x, double robot_y, double robot_yaw, double *min_x, double *min_y, double *max_x, double *max_y)
Update the bounds of the master costmap by this layer's update dimensions.
virtual void deactivate()
Deactivate the layer.
virtual void activate()
Activate the layer.
void clearArea(int start_x, int start_y, int end_x, int end_y, bool invert) override
Clear an area in the constituent costmaps with the given dimension if invert, then clear everything e...
virtual void reset()
Reset this costmap.
virtual bool isClearable()
If clearing operations should be processed on this layer or not.
virtual void updateCosts(nav2_costmap_2d::Costmap2D &master_grid, int min_i, int min_j, int max_i, int max_j)
Update the costs in the master costmap in the window.