15 #include "nav2_costmap_2d/plugin_container_layer.hpp"
17 #include "nav2_costmap_2d/costmap_math.hpp"
18 #include "nav2_costmap_2d/footprint.hpp"
19 #include "nav2_ros_common/node_utils.hpp"
20 #include "rclcpp/parameter_events_filter.hpp"
21 #include "pluginlib/class_list_macros.hpp"
32 auto node = node_.lock();
35 throw std::runtime_error{
"Failed to lock node"};
38 nav2::declare_parameter_if_not_declared(node, name_ +
"." +
"enabled",
39 rclcpp::ParameterValue(
true));
40 nav2::declare_parameter_if_not_declared(node, name_ +
"." +
"plugins",
41 rclcpp::ParameterValue(std::vector<std::string>{}));
42 nav2::declare_parameter_if_not_declared(node, name_ +
"." +
"combination_method",
43 rclcpp::ParameterValue(1));
45 node->get_parameter(name_ +
"." +
"enabled", enabled_);
46 node->get_parameter(name_ +
"." +
"plugins", plugin_names_);
48 int combination_method_param{};
49 node->get_parameter(name_ +
"." +
"combination_method", combination_method_param);
52 dyn_params_handler_ = node->add_on_set_parameters_callback(
56 std::placeholders::_1));
58 plugin_types_.resize(plugin_names_.size());
60 for (
unsigned int i = 0; i < plugin_names_.size(); ++i) {
61 plugin_types_[i] = nav2::get_plugin_type_param(node, name_ +
"." + plugin_names_[i]);
62 std::shared_ptr<Layer> plugin = plugin_loader_.createSharedInstance(plugin_types_[i]);
63 addPlugin(plugin, plugin_names_[i]);
66 default_value_ = nav2_costmap_2d::NO_INFORMATION;
72 void PluginContainerLayer::addPlugin(std::shared_ptr<Layer> plugin, std::string layer_name)
74 plugins_.push_back(plugin);
75 auto node = node_.lock();
76 plugin->initialize(layered_costmap_, name_ +
"." + layer_name, tf_, node, callback_group_);
88 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
91 (*plugin)->updateBounds(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
102 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
107 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
110 (*plugin)->updateCosts(*
this, min_i, min_j, max_i, max_j);
113 switch (combination_method_) {
115 updateWithOverwrite(master_grid, min_i, min_j, max_i, max_j);
118 updateWithMax(master_grid, min_i, min_j, max_i, max_j);
121 updateWithMaxWithoutUnknownOverwrite(master_grid, min_i, min_j, max_i, max_j);
132 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
135 (*plugin)->activate();
141 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
144 (*plugin)->deactivate();
150 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
161 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
164 (*plugin)->onFootprintChanged();
170 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
176 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
179 (*plugin)->matchSize();
185 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
188 if((*plugin)->isClearable()) {
198 for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
201 auto costmap_layer = std::dynamic_pointer_cast<nav2_costmap_2d::CostmapLayer>(*plugin);
202 if ((*plugin)->isClearable() && costmap_layer !=
nullptr) {
203 costmap_layer->clearArea(start_x, start_y, end_x, end_y, invert);
209 std::vector<rclcpp::Parameter> parameters)
211 std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
212 rcl_interfaces::msg::SetParametersResult result;
214 for (
auto parameter : parameters) {
215 const auto & param_type = parameter.get_type();
216 const auto & param_name = parameter.get_name();
217 if (param_name.find(name_ +
".") != 0) {
221 if (param_type == ParameterType::PARAMETER_INTEGER) {
222 if (param_name == name_ +
"." +
"combination_method") {
225 }
else if (param_type == ParameterType::PARAMETER_BOOL) {
226 if (param_name == name_ +
"." +
"enabled" && enabled_ != parameter.as_bool()) {
227 enabled_ = parameter.as_bool();
233 result.successful =
true;
A 2D costmap provides a mapping between points in the world and their associated "costs".
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
Resize the costmap.
double getResolution() const
Accessor for the resolution of the costmap.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
double getOriginY() const
Accessor for the y origin of the costmap.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
double getOriginX() const
Accessor for the x origin of the costmap.
virtual void clearArea(int start_x, int start_y, int end_x, int end_y, bool invert)
Clear an are in the costmap with the given dimension if invert, then clear everything except these di...
CombinationMethod combination_method_from_int(const int value)
Converts an integer to a CombinationMethod enum and logs on failure.
Abstract class for layered costmap plugin implementations.
Costmap2D * getCostmap()
Get the costmap pointer to the master costmap.
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.
@ MaxWithoutUnknownOverwrite