Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
40 commits
Select commit Hold shift + click to select a range
75635ff
updated CMakeLists.txt to include plugin_container_layer
alexanderjyuen Nov 21, 2024
df537af
added plugin container layer to costmap_plugins.xml
alexanderjyuen Nov 21, 2024
eb7b986
initial commit of plugin container layer
alexanderjyuen Nov 21, 2024
5cfbbbb
fixed plugin namespace
alexanderjyuen Nov 27, 2024
5c0971f
fixed message_filter
alexanderjyuen Nov 27, 2024
733ce92
linting
alexanderjyuen Nov 28, 2024
f415750
modified addPlugin method to also take layer name
alexanderjyuen Dec 2, 2024
dc9cd63
reverted default plugins to be empty, free costmap_ during layer dest…
alexanderjyuen Dec 2, 2024
0d31aad
CMake changes to test plugin container layer
alexanderjyuen Dec 2, 2024
82e69ca
added helper method to add plugin container layer
alexanderjyuen Dec 2, 2024
118e2b3
added initial implementation of plugin container tests
alexanderjyuen Dec 2, 2024
049ad7c
added enable to dynamic params, removed unecessary comments, removed …
alexanderjyuen Dec 3, 2024
468e869
cleaned up and added additional tests
alexanderjyuen Dec 3, 2024
16819e4
added Apache copyrights
alexanderjyuen Dec 3, 2024
08e4e56
linting for ament_cpplint
alexanderjyuen Dec 4, 2024
5d68254
added example file for plugin_container_layer to nav2_bringup
alexanderjyuen Nov 28, 2024
a0c11b4
Merge branch 'main' into feature-plugin-container-layer
alexanderjyuen Dec 4, 2024
0bb6c53
removed unused rolling_window_ member variable
alexanderjyuen Dec 4, 2024
36960a3
removed default plugins and plugin types
alexanderjyuen Dec 4, 2024
b96587f
switched to using CombinationMethod enum, added updateWithMaxWithoutU…
alexanderjyuen Dec 4, 2024
5f05d44
removed combined_costmap_
alexanderjyuen Dec 4, 2024
9d92e3c
fixed layer naming and accomodating tests
alexanderjyuen Dec 4, 2024
ddceccb
removed nav2_params_plugin_container_layer.yaml
alexanderjyuen Dec 4, 2024
4afd4f9
added more comprehensive checks for checking if layers are clearable
alexanderjyuen Dec 4, 2024
34d0c57
added dynamics parameter handling, fixed current_ setting, increased …
alexanderjyuen Dec 5, 2024
b25f2a3
removed unnecessary locks, added default value
alexanderjyuen Dec 5, 2024
f282191
removed unecessary resetMap
alexanderjyuen Dec 5, 2024
06b1fbd
added layer resetting when reset method is called
alexanderjyuen Dec 6, 2024
ac3b013
swapped logic for isClearable
alexanderjyuen Dec 6, 2024
822bf1f
fixed breaking tests, removed unnecessary combined_costmap_
alexanderjyuen Dec 7, 2024
58e26e4
consolidated initialization for loops
alexanderjyuen Dec 7, 2024
5a66397
switched default_value_ to NO_INFORMATION
alexanderjyuen Dec 7, 2024
00e838d
added clearArea function
alexanderjyuen Dec 8, 2024
64f0b51
added clearArea test
alexanderjyuen Dec 9, 2024
3c2eb68
removed TODO message
alexanderjyuen Dec 11, 2024
b2926d1
removed constructor and destructors since they do nothing
alexanderjyuen Dec 11, 2024
ce437aa
added check on costmap layer to see if it is clearable first
alexanderjyuen Dec 11, 2024
0e86021
fixed tests for clearing functionality
alexanderjyuen Dec 11, 2024
bb91a7f
added try catch around initialization of plugins
alexanderjyuen Dec 11, 2024
b430429
fixed indents
alexanderjyuen Dec 11, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions nav2_costmap_2d/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,7 @@ add_library(layers SHARED
plugins/voxel_layer.cpp
plugins/range_sensor_layer.cpp
plugins/denoise_layer.cpp
plugins/plugin_container_layer.cpp
)
target_include_directories(layers
PUBLIC
Expand Down
3 changes: 3 additions & 0 deletions nav2_costmap_2d/costmap_plugins.xml
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,9 @@
<class type="nav2_costmap_2d::DenoiseLayer" base_class_type="nav2_costmap_2d::Layer">
<description>Filters noise-induced freestanding obstacles or small obstacles groups</description>
</class>
<class type="nav2_costmap_2d::PluginContainerLayer" base_class_type="nav2_costmap_2d::Layer">
<description>Plugin to group different layers within the same costmap</description>
</class>
</library>

<library path="filters">
Expand Down
128 changes: 128 additions & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/plugin_container_layer.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,128 @@
// Copyright (c) 2024 Polymath Robotics, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef NAV2_COSTMAP_2D__PLUGIN_CONTAINER_LAYER_HPP_
#define NAV2_COSTMAP_2D__PLUGIN_CONTAINER_LAYER_HPP_

#include <Eigen/Dense>
#include <cmath>
#include <memory>
#include <string>
#include <vector>
#include "rclcpp/rclcpp.hpp"
#include "nav2_costmap_2d/layer.hpp"
#include "nav2_costmap_2d/layered_costmap.hpp"
#include "nav2_costmap_2d/costmap_layer.hpp"
#include "nav2_costmap_2d/observation_buffer.hpp"
#include "nav2_costmap_2d/inflation_layer.hpp"
#include "tf2_ros/message_filter.h"
#include "message_filters/subscriber.hpp"
#include "pluginlib/class_loader.hpp"

using nav2_costmap_2d::LETHAL_OBSTACLE;
using nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE;
using nav2_costmap_2d::NO_INFORMATION;
using rcl_interfaces::msg::ParameterType;
namespace nav2_costmap_2d
{
/**
* @class PluginContainerLayer
* @brief Holds a list of plugins and applies them only to the specific layer
*/
class PluginContainerLayer : public CostmapLayer
{
public:
/**
* @brief Initialization process of layer on startup
*/
virtual void onInitialize();
/**
* @brief Update the bounds of the master costmap by this layer's update
*dimensions
* @param robot_x X pose of robot
* @param robot_y Y pose of robot
* @param robot_yaw Robot orientation
* @param min_x X min map coord of the window to update
* @param min_y Y min map coord of the window to update
* @param max_x X max map coord of the window to update
* @param max_y Y max map coord of the window to update
*/
virtual void updateBounds(
double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
double * min_y,
double * max_x,
double * max_y);
/**
* @brief Update the costs in the master costmap in the window
* @param master_grid The master costmap grid to update
* @param min_x X min map coord of the window to update
* @param min_y Y min map coord of the window to update
* @param max_x X max map coord of the window to update
* @param max_y Y max map coord of the window to update
*/
virtual void updateCosts(
nav2_costmap_2d::Costmap2D & master_grid,
int min_i,
int min_j,
int max_i,
int max_j);
virtual void onFootprintChanged();
/** @brief Update the footprint to match size of the parent costmap. */
virtual void matchSize();
/**
* @brief Deactivate the layer
*/
virtual void deactivate();
/**
* @brief Activate the layer
*/
virtual void activate();
/**
* @brief Reset this costmap
*/
virtual void reset();
/**
* @brief If clearing operations should be processed on this layer or not
*/
virtual bool isClearable();
/**
* @brief Clear an area in the constituent costmaps with the given dimension
* if invert, then clear everything except these dimensions
*/
void clearArea(int start_x, int start_y, int end_x, int end_y, bool invert) override;

void addPlugin(std::shared_ptr<Layer> plugin, std::string layer_name);
pluginlib::ClassLoader<Layer> plugin_loader_{"nav2_costmap_2d", "nav2_costmap_2d::Layer"};
/**
* @brief Callback executed when a parameter change is detected
* @param event ParameterEvent message
*/
rcl_interfaces::msg::SetParametersResult dynamicParametersCallback(
std::vector<rclcpp::Parameter> parameters);

private:
/// @brief Dynamic parameters handler
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
dyn_params_handler_;

nav2_costmap_2d::CombinationMethod combination_method_;
std::vector<std::shared_ptr<Layer>> plugins_;
std::vector<std::string> plugin_names_;
std::vector<std::string> plugin_types_;
};
} // namespace nav2_costmap_2d
#endif // NAV2_COSTMAP_2D__PLUGIN_CONTAINER_LAYER_HPP_
234 changes: 234 additions & 0 deletions nav2_costmap_2d/plugins/plugin_container_layer.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,234 @@
// Copyright (c) 2024 Polymath Robotics, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "nav2_costmap_2d/plugin_container_layer.hpp"

#include "nav2_costmap_2d/costmap_math.hpp"
#include "nav2_costmap_2d/footprint.hpp"
#include "nav2_util/node_utils.hpp"
#include "rclcpp/parameter_events_filter.hpp"
#include "pluginlib/class_list_macros.hpp"

PLUGINLIB_EXPORT_CLASS(nav2_costmap_2d::PluginContainerLayer, nav2_costmap_2d::Layer)

using std::vector;

namespace nav2_costmap_2d
{

void PluginContainerLayer::onInitialize()
{
auto node = node_.lock();

if (!node) {
throw std::runtime_error{"Failed to lock node"};
}

nav2_util::declare_parameter_if_not_declared(node, name_ + "." + "enabled",
rclcpp::ParameterValue(true));
nav2_util::declare_parameter_if_not_declared(node, name_ + "." + "plugins",
rclcpp::ParameterValue(std::vector<std::string>{}));
nav2_util::declare_parameter_if_not_declared(node, name_ + "." + "combination_method",
rclcpp::ParameterValue(1));

node->get_parameter(name_ + "." + "enabled", enabled_);
node->get_parameter(name_ + "." + "plugins", plugin_names_);

int combination_method_param{};
node->get_parameter(name_ + "." + "combination_method", combination_method_param);
combination_method_ = combination_method_from_int(combination_method_param);

dyn_params_handler_ = node->add_on_set_parameters_callback(
std::bind(
&PluginContainerLayer::dynamicParametersCallback,
this,
std::placeholders::_1));

plugin_types_.resize(plugin_names_.size());

for (unsigned int i = 0; i < plugin_names_.size(); ++i) {
Comment thread
alexanderjyuen marked this conversation as resolved.
plugin_types_[i] = nav2_util::get_plugin_type_param(node, name_ + "." + plugin_names_[i]);
std::shared_ptr<Layer> plugin = plugin_loader_.createSharedInstance(plugin_types_[i]);
Comment thread
alexanderjyuen marked this conversation as resolved.
addPlugin(plugin, plugin_names_[i]);
}

default_value_ = nav2_costmap_2d::NO_INFORMATION;

PluginContainerLayer::matchSize();
current_ = true;
}

void PluginContainerLayer::addPlugin(std::shared_ptr<Layer> plugin, std::string layer_name)
{
plugins_.push_back(plugin);
auto node = node_.lock();
plugin->initialize(layered_costmap_, name_ + "." + layer_name, tf_, node, callback_group_);
}

void PluginContainerLayer::updateBounds(
double robot_x,
double robot_y,
double robot_yaw,
double * min_x,
double * min_y,
double * max_x,
double * max_y)
{
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
++plugin)
{
(*plugin)->updateBounds(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
}
}

void PluginContainerLayer::updateCosts(
nav2_costmap_2d::Costmap2D & master_grid,
int min_i,
int min_j,
int max_i,
int max_j)
{
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
if (!enabled_) {
return;
}

for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
++plugin)
{
(*plugin)->updateCosts(*this, min_i, min_j, max_i, max_j);
}

switch (combination_method_) {
Comment thread
alexanderjyuen marked this conversation as resolved.
case CombinationMethod::Overwrite:
updateWithOverwrite(master_grid, min_i, min_j, max_i, max_j);
break;
case CombinationMethod::Max:
updateWithMax(master_grid, min_i, min_j, max_i, max_j);
break;
case CombinationMethod::MaxWithoutUnknownOverwrite:
updateWithMaxWithoutUnknownOverwrite(master_grid, min_i, min_j, max_i, max_j);
break;
default: // Nothing
break;
}

current_ = true;
}

void PluginContainerLayer::activate()
{
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
++plugin)
{
(*plugin)->activate();
}
}

void PluginContainerLayer::deactivate()
{
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
++plugin)
{
(*plugin)->deactivate();
}
}

void PluginContainerLayer::reset()
{
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
++plugin)
{
(*plugin)->reset();
}
resetMaps();
current_ = false;
}

void PluginContainerLayer::onFootprintChanged()
{
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
++plugin)
{
(*plugin)->onFootprintChanged();
}
}

void PluginContainerLayer::matchSize()
{
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
Costmap2D * master = layered_costmap_->getCostmap();
resizeMap(
master->getSizeInCellsX(), master->getSizeInCellsY(),
master->getResolution(), master->getOriginX(), master->getOriginY());

for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
++plugin)
{
(*plugin)->matchSize();
}
}

bool PluginContainerLayer::isClearable()
{
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
++plugin)
{
if((*plugin)->isClearable()) {
return true;
}
}
return false;
}

Comment thread
SteveMacenski marked this conversation as resolved.
void PluginContainerLayer::clearArea(int start_x, int start_y, int end_x, int end_y, bool invert)
{
CostmapLayer::clearArea(start_x, start_y, end_x, end_y, invert);
for (vector<std::shared_ptr<Layer>>::iterator plugin = plugins_.begin(); plugin != plugins_.end();
++plugin)
{
auto costmap_layer = std::dynamic_pointer_cast<nav2_costmap_2d::CostmapLayer>(*plugin);
Comment thread
SteveMacenski marked this conversation as resolved.
if ((*plugin)->isClearable() && costmap_layer != nullptr) {
costmap_layer->clearArea(start_x, start_y, end_x, end_y, invert);
}
}
}

rcl_interfaces::msg::SetParametersResult PluginContainerLayer::dynamicParametersCallback(
std::vector<rclcpp::Parameter> parameters)
{
std::lock_guard<Costmap2D::mutex_t> guard(*getMutex());
rcl_interfaces::msg::SetParametersResult result;

for (auto parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();

if (param_type == ParameterType::PARAMETER_INTEGER) {
if (param_name == name_ + "." + "combination_method") {
combination_method_ = combination_method_from_int(parameter.as_int());
}
} else if (param_type == ParameterType::PARAMETER_BOOL) {
if (param_name == name_ + "." + "enabled" && enabled_ != parameter.as_bool()) {
enabled_ = parameter.as_bool();
current_ = false;
}
}
}

result.successful = true;
return result;
}

} // namespace nav2_costmap_2d
11 changes: 8 additions & 3 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,9 +177,14 @@ Costmap2DROS::on_configure(const rclcpp_lifecycle::State & /*state*/)
layered_costmap_->addPlugin(plugin);

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

lock.unlock();

Expand Down
Loading