Skip to content

Commit 01eefc0

Browse files
alexanderjyuenSteveMacenski
authored andcommitted
nav2_costmap_2d plugin container layer (#4781)
* updated CMakeLists.txt to include plugin_container_layer Signed-off-by: alexander <alex@polymathrobotics.com> * added plugin container layer to costmap_plugins.xml Signed-off-by: alexander <alex@polymathrobotics.com> * initial commit of plugin container layer Signed-off-by: alexander <alex@polymathrobotics.com> * fixed plugin namespace Signed-off-by: alexander <alex@polymathrobotics.com> * fixed message_filter Signed-off-by: alexander <alex@polymathrobotics.com> * linting Signed-off-by: alexander <alex@polymathrobotics.com> * modified addPlugin method to also take layer name Signed-off-by: alexander <alex@polymathrobotics.com> * reverted default plugins to be empty, free costmap_ during layer destruction, changed addPlugin to take layer name as an argument Signed-off-by: alexander <alex@polymathrobotics.com> * CMake changes to test plugin container layer Signed-off-by: alexander <alex@polymathrobotics.com> * added helper method to add plugin container layer Signed-off-by: alexander <alex@polymathrobotics.com> * added initial implementation of plugin container tests Signed-off-by: alexander <alex@polymathrobotics.com> * added enable to dynamic params, removed unecessary comments, removed unecessary members Signed-off-by: alexander <alex@polymathrobotics.com> * cleaned up and added additional tests Signed-off-by: alexander <alex@polymathrobotics.com> * added Apache copyrights Signed-off-by: alexander <alex@polymathrobotics.com> * linting for ament_cpplint Signed-off-by: alexander <alex@polymathrobotics.com> * added example file for plugin_container_layer to nav2_bringup Signed-off-by: alexander <alex@polymathrobotics.com> * removed unused rolling_window_ member variable Signed-off-by: alexander <alex@polymathrobotics.com> * removed default plugins and plugin types Signed-off-by: alexander <alex@polymathrobotics.com> * switched to using CombinationMethod enum, added updateWithMaxWithoutUnknownOverwrite case Signed-off-by: alexander <alex@polymathrobotics.com> * removed combined_costmap_ Signed-off-by: alexander <alex@polymathrobotics.com> * fixed layer naming and accomodating tests Signed-off-by: alexander <alex@polymathrobotics.com> * removed nav2_params_plugin_container_layer.yaml Signed-off-by: alexander <alex@polymathrobotics.com> * added more comprehensive checks for checking if layers are clearable Signed-off-by: alexander <alex@polymathrobotics.com> * added dynamics parameter handling, fixed current_ setting, increased test coverage Signed-off-by: alexander <alex@polymathrobotics.com> * removed unnecessary locks, added default value Signed-off-by: alexander <alex@polymathrobotics.com> * removed unecessary resetMap Signed-off-by: alexander <alex@polymathrobotics.com> * added layer resetting when reset method is called Signed-off-by: alexander <alex@polymathrobotics.com> * swapped logic for isClearable Signed-off-by: alexander <alex@polymathrobotics.com> * fixed breaking tests, removed unnecessary combined_costmap_ Signed-off-by: alexander <alex@polymathrobotics.com> * consolidated initialization for loops Signed-off-by: alexander <alex@polymathrobotics.com> * switched default_value_ to NO_INFORMATION Signed-off-by: alexander <alex@polymathrobotics.com> * added clearArea function Signed-off-by: alexander <alex@polymathrobotics.com> * added clearArea test Signed-off-by: alexander <alex@polymathrobotics.com> * removed TODO message Signed-off-by: alexander <alex@polymathrobotics.com> * removed constructor and destructors since they do nothing Signed-off-by: alexander <alex@polymathrobotics.com> * added check on costmap layer to see if it is clearable first Signed-off-by: alexander <alex@polymathrobotics.com> * fixed tests for clearing functionality Signed-off-by: alexander <alex@polymathrobotics.com> * added try catch around initialization of plugins Signed-off-by: alexander <alex@polymathrobotics.com> * fixed indents Signed-off-by: alexander <alex@polymathrobotics.com> --------- Signed-off-by: alexander <alex@polymathrobotics.com>
1 parent d3b7480 commit 01eefc0

File tree

8 files changed

+1094
-3
lines changed

8 files changed

+1094
-3
lines changed

nav2_costmap_2d/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -88,6 +88,7 @@ add_library(layers SHARED
8888
plugins/voxel_layer.cpp
8989
plugins/range_sensor_layer.cpp
9090
plugins/denoise_layer.cpp
91+
plugins/plugin_container_layer.cpp
9192
)
9293
add_library(${PROJECT_NAME}::layers ALIAS layers)
9394
ament_target_dependencies(layers

nav2_costmap_2d/costmap_plugins.xml

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -18,6 +18,9 @@
1818
<class type="nav2_costmap_2d::DenoiseLayer" base_class_type="nav2_costmap_2d::Layer">
1919
<description>Filters noise-induced freestanding obstacles or small obstacles groups</description>
2020
</class>
21+
<class type="nav2_costmap_2d::PluginContainerLayer" base_class_type="nav2_costmap_2d::Layer">
22+
<description>Plugin to group different layers within the same costmap</description>
23+
</class>
2124
</library>
2225

2326
<library path="filters">
Lines changed: 128 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,128 @@
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+
#ifndef NAV2_COSTMAP_2D__PLUGIN_CONTAINER_LAYER_HPP_
16+
#define NAV2_COSTMAP_2D__PLUGIN_CONTAINER_LAYER_HPP_
17+
18+
#include <Eigen/Dense>
19+
#include <cmath>
20+
#include <memory>
21+
#include <string>
22+
#include <vector>
23+
#include "rclcpp/rclcpp.hpp"
24+
#include "nav2_costmap_2d/layer.hpp"
25+
#include "nav2_costmap_2d/layered_costmap.hpp"
26+
#include "nav2_costmap_2d/costmap_layer.hpp"
27+
#include "nav2_costmap_2d/observation_buffer.hpp"
28+
#include "nav2_costmap_2d/inflation_layer.hpp"
29+
#include "tf2_ros/message_filter.h"
30+
#include "message_filters/subscriber.hpp"
31+
#include "pluginlib/class_loader.hpp"
32+
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;
37+
namespace nav2_costmap_2d
38+
{
39+
/**
40+
* @class PluginContainerLayer
41+
* @brief Holds a list of plugins and applies them only to the specific layer
42+
*/
43+
class PluginContainerLayer : public CostmapLayer
44+
{
45+
public:
46+
/**
47+
* @brief Initialization process of layer on startup
48+
*/
49+
virtual void onInitialize();
50+
/**
51+
* @brief Update the bounds of the master costmap by this layer's update
52+
*dimensions
53+
* @param robot_x X pose of robot
54+
* @param robot_y Y pose of robot
55+
* @param robot_yaw Robot orientation
56+
* @param min_x X min map coord of the window to update
57+
* @param min_y Y min map coord of the window to update
58+
* @param max_x X max map coord of the window to update
59+
* @param max_y Y max map coord of the window to update
60+
*/
61+
virtual void updateBounds(
62+
double robot_x,
63+
double robot_y,
64+
double robot_yaw,
65+
double * min_x,
66+
double * min_y,
67+
double * max_x,
68+
double * max_y);
69+
/**
70+
* @brief Update the costs in the master costmap in the window
71+
* @param master_grid The master costmap grid to update
72+
* @param min_x X min map coord of the window to update
73+
* @param min_y Y min map coord of the window to update
74+
* @param max_x X max map coord of the window to update
75+
* @param max_y Y max map coord of the window to update
76+
*/
77+
virtual void updateCosts(
78+
nav2_costmap_2d::Costmap2D & master_grid,
79+
int min_i,
80+
int min_j,
81+
int max_i,
82+
int max_j);
83+
virtual void onFootprintChanged();
84+
/** @brief Update the footprint to match size of the parent costmap. */
85+
virtual void matchSize();
86+
/**
87+
* @brief Deactivate the layer
88+
*/
89+
virtual void deactivate();
90+
/**
91+
* @brief Activate the layer
92+
*/
93+
virtual void activate();
94+
/**
95+
* @brief Reset this costmap
96+
*/
97+
virtual void reset();
98+
/**
99+
* @brief If clearing operations should be processed on this layer or not
100+
*/
101+
virtual bool isClearable();
102+
/**
103+
* @brief Clear an area in the constituent costmaps with the given dimension
104+
* if invert, then clear everything except these dimensions
105+
*/
106+
void clearArea(int start_x, int start_y, int end_x, int end_y, bool invert) override;
107+
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"};
110+
/**
111+
* @brief Callback executed when a parameter change is detected
112+
* @param event ParameterEvent message
113+
*/
114+
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(
115+
std::vector<rclcpp::Parameter> parameters);
116+
117+
private:
118+
/// @brief Dynamic parameters handler
119+
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
120+
dyn_params_handler_;
121+
122+
nav2_costmap_2d::CombinationMethod combination_method_;
123+
std::vector<std::shared_ptr<Layer>> plugins_;
124+
std::vector<std::string> plugin_names_;
125+
std::vector<std::string> plugin_types_;
126+
};
127+
} // namespace nav2_costmap_2d
128+
#endif // NAV2_COSTMAP_2D__PLUGIN_CONTAINER_LAYER_HPP_
Lines changed: 234 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,234 @@
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_util/node_utils.hpp"
20+
#include "rclcpp/parameter_events_filter.hpp"
21+
#include "pluginlib/class_list_macros.hpp"
22+
23+
PLUGINLIB_EXPORT_CLASS(nav2_costmap_2d::PluginContainerLayer, nav2_costmap_2d::Layer)
24+
25+
using std::vector;
26+
27+
namespace nav2_costmap_2d
28+
{
29+
30+
void PluginContainerLayer::onInitialize()
31+
{
32+
auto node = node_.lock();
33+
34+
if (!node) {
35+
throw std::runtime_error{"Failed to lock node"};
36+
}
37+
38+
nav2_util::declare_parameter_if_not_declared(node, name_ + "." + "enabled",
39+
rclcpp::ParameterValue(true));
40+
nav2_util::declare_parameter_if_not_declared(node, name_ + "." + "plugins",
41+
rclcpp::ParameterValue(std::vector<std::string>{}));
42+
nav2_util::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(
54+
&PluginContainerLayer::dynamicParametersCallback,
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_util::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+
68+
PluginContainerLayer::matchSize();
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+
79+
void PluginContainerLayer::updateBounds(
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+
95+
void PluginContainerLayer::updateCosts(
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_) {
114+
case CombinationMethod::Overwrite:
115+
updateWithOverwrite(master_grid, min_i, min_j, max_i, max_j);
116+
break;
117+
case CombinationMethod::Max:
118+
updateWithMax(master_grid, min_i, min_j, max_i, max_j);
119+
break;
120+
case CombinationMethod::MaxWithoutUnknownOverwrite:
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+
130+
void PluginContainerLayer::activate()
131+
{
132+
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
133+
++plugin)
134+
{
135+
(*plugin)->activate();
136+
}
137+
}
138+
139+
void PluginContainerLayer::deactivate()
140+
{
141+
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
142+
++plugin)
143+
{
144+
(*plugin)->deactivate();
145+
}
146+
}
147+
148+
void PluginContainerLayer::reset()
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+
159+
void PluginContainerLayer::onFootprintChanged()
160+
{
161+
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
162+
++plugin)
163+
{
164+
(*plugin)->onFootprintChanged();
165+
}
166+
}
167+
168+
void PluginContainerLayer::matchSize()
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+
183+
bool PluginContainerLayer::isClearable()
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+
218+
if (param_type == ParameterType::PARAMETER_INTEGER) {
219+
if (param_name == name_ + "." + "combination_method") {
220+
combination_method_ = combination_method_from_int(parameter.as_int());
221+
}
222+
} else if (param_type == ParameterType::PARAMETER_BOOL) {
223+
if (param_name == name_ + "." + "enabled" && enabled_ != parameter.as_bool()) {
224+
enabled_ = parameter.as_bool();
225+
current_ = false;
226+
}
227+
}
228+
}
229+
230+
result.successful = true;
231+
return result;
232+
}
233+
234+
} // namespace nav2_costmap_2d

nav2_costmap_2d/src/costmap_2d_ros.cpp

Lines changed: 8 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -186,9 +186,14 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
186186
layered_costmap_->addPlugin(plugin);
187187

188188
// TODO(mjeronimo): instead of get(), use a shared ptr
189-
plugin->initialize(
190-
layered_costmap_.get(), plugin_names_[i], tf_buffer_.get(),
191-
shared_from_this(), callback_group_);
189+
try {
190+
plugin->initialize(layered_costmap_.get(), plugin_names_[i], tf_buffer_.get(),
191+
shared_from_this(), callback_group_);
192+
} catch (const std::exception & e) {
193+
RCLCPP_ERROR(get_logger(), "Failed to initialize costmap plugin %s! %s.",
194+
plugin_names_[i].c_str(), e.what());
195+
return nav2_util::CallbackReturn::FAILURE;
196+
}
192197

193198
lock.unlock();
194199

0 commit comments

Comments
 (0)