Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
plugin_container_layer.cpp
1 // Copyright (c) 2024 Polymath Robotics, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #include "nav2_costmap_2d/plugin_container_layer.hpp"
16 
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"
22 
24 
25 using std::vector;
26 
27 namespace nav2_costmap_2d
28 {
29 
31 {
32  auto node = node_.lock();
33 
34  if (!node) {
35  throw std::runtime_error{"Failed to lock node"};
36  }
37 
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));
44 
45  node->get_parameter(name_ + "." + "enabled", enabled_);
46  node->get_parameter(name_ + "." + "plugins", plugin_names_);
47 
48  int combination_method_param{};
49  node->get_parameter(name_ + "." + "combination_method", combination_method_param);
50  combination_method_ = combination_method_from_int(combination_method_param);
51 
52  dyn_params_handler_ = node->add_on_set_parameters_callback(
53  std::bind(
55  this,
56  std::placeholders::_1));
57 
58  plugin_types_.resize(plugin_names_.size());
59 
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]);
64  }
65 
66  default_value_ = nav2_costmap_2d::NO_INFORMATION;
67 
69  current_ = true;
70 }
71 
72 void PluginContainerLayer::addPlugin(std::shared_ptr<Layer> plugin, std::string layer_name)
73 {
74  plugins_.push_back(plugin);
75  auto node = node_.lock();
76  plugin->initialize(layered_costmap_, name_ + "." + layer_name, tf_, node, callback_group_);
77 }
78 
80  double robot_x,
81  double robot_y,
82  double robot_yaw,
83  double * min_x,
84  double * min_y,
85  double * max_x,
86  double * max_y)
87 {
88  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
89  ++plugin)
90  {
91  (*plugin)->updateBounds(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
92  }
93 }
94 
96  nav2_costmap_2d::Costmap2D & master_grid,
97  int min_i,
98  int min_j,
99  int max_i,
100  int max_j)
101 {
102  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
103  if (!enabled_) {
104  return;
105  }
106 
107  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
108  ++plugin)
109  {
110  (*plugin)->updateCosts(*this, min_i, min_j, max_i, max_j);
111  }
112 
113  switch (combination_method_) {
115  updateWithOverwrite(master_grid, min_i, min_j, max_i, max_j);
116  break;
118  updateWithMax(master_grid, min_i, min_j, max_i, max_j);
119  break;
121  updateWithMaxWithoutUnknownOverwrite(master_grid, min_i, min_j, max_i, max_j);
122  break;
123  default: // Nothing
124  break;
125  }
126 
127  current_ = true;
128 }
129 
131 {
132  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
133  ++plugin)
134  {
135  (*plugin)->activate();
136  }
137 }
138 
140 {
141  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
142  ++plugin)
143  {
144  (*plugin)->deactivate();
145  }
146 }
147 
149 {
150  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
151  ++plugin)
152  {
153  (*plugin)->reset();
154  }
155  resetMaps();
156  current_ = false;
157 }
158 
160 {
161  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
162  ++plugin)
163  {
164  (*plugin)->onFootprintChanged();
165  }
166 }
167 
169 {
170  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
171  Costmap2D * master = layered_costmap_->getCostmap();
172  resizeMap(
173  master->getSizeInCellsX(), master->getSizeInCellsY(),
174  master->getResolution(), master->getOriginX(), master->getOriginY());
175 
176  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
177  ++plugin)
178  {
179  (*plugin)->matchSize();
180  }
181 }
182 
184 {
185  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
186  ++plugin)
187  {
188  if((*plugin)->isClearable()) {
189  return true;
190  }
191  }
192  return false;
193 }
194 
195 void PluginContainerLayer::clearArea(int start_x, int start_y, int end_x, int end_y, bool invert)
196 {
197  CostmapLayer::clearArea(start_x, start_y, end_x, end_y, invert);
198  for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
199  ++plugin)
200  {
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);
204  }
205  }
206 }
207 
208 rcl_interfaces::msg::SetParametersResult PluginContainerLayer::dynamicParametersCallback(
209  std::vector<rclcpp::Parameter> parameters)
210 {
211  std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
212  rcl_interfaces::msg::SetParametersResult result;
213 
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) {
218  continue;
219  }
220 
221  if (param_type == ParameterType::PARAMETER_INTEGER) {
222  if (param_name == name_ + "." + "combination_method") {
223  combination_method_ = combination_method_from_int(parameter.as_int());
224  }
225  } else if (param_type == ParameterType::PARAMETER_BOOL) {
226  if (param_name == name_ + "." + "enabled" && enabled_ != parameter.as_bool()) {
227  enabled_ = parameter.as_bool();
228  current_ = false;
229  }
230  }
231  }
232 
233  result.successful = true;
234  return result;
235 }
236 
237 } // namespace nav2_costmap_2d
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:69
void resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x, double origin_y)
Resize the costmap.
Definition: costmap_2d.cpp:110
double getResolution() const
Accessor for the resolution of the costmap.
Definition: costmap_2d.cpp:576
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
Definition: costmap_2d.cpp:546
virtual void resetMaps()
Resets the costmap and static_map to be unknown space.
Definition: costmap_2d.cpp:124
double getOriginY() const
Accessor for the y origin of the costmap.
Definition: costmap_2d.cpp:571
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.
Definition: costmap_2d.cpp:551
double getOriginX() const
Accessor for the x origin of the costmap.
Definition: costmap_2d.cpp:566
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.
Definition: layer.hpp:59
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.