Skip to content

Commit

Permalink
Humble release 11: May 23, 2024 (#4365)
Browse files Browse the repository at this point in the history
* Scale cost critic's weight when dynamically updated (#4246)

* Scale cost critic's weight when dynamically updated

Signed-off-by: pepisg <[email protected]>

* sign off

Signed-off-by: pepisg <[email protected]>

---------

Signed-off-by: pepisg <[email protected]>

* Add expanding the ~/ to the full home dir of user in the path to the map yaml.  (#4258)

* Add user home expander of home sequence

Signed-off-by: Wiktor Bajor <[email protected]>

* Add passing home dir as string instead of const char*

Signed-off-by: Wiktor Bajor <[email protected]>

* Add docs

Signed-off-by: Wiktor Bajor <[email protected]>

* Fix function declaration

Signed-off-by: Wiktor Bajor <[email protected]>

* Fix linter issues

Signed-off-by: Wiktor Bajor <[email protected]>

* Uncrustify linter

Signed-off-by: Wiktor Bajor <[email protected]>

* Uncrustify linter

Signed-off-by: Wiktor Bajor <[email protected]>

* Uncrustify linter: remove remove whitespace

Signed-off-by: Wiktor Bajor <[email protected]>

---------

Signed-off-by: Wiktor Bajor <[email protected]>

* Implement Critic for Velocity Deadband Hardware Constraints (#4256)

* Adding new velocity deadband critic.

- add some tests
- cast double to float
- add new features from "main" branch

- fix formating

- add cost test
- fix linting issue
- add README

Signed-off-by: Denis Sokolov <[email protected]>

* Remove velocity deadband critic from defaults

Signed-off-by: Denis Sokolov <[email protected]>

* remove old weight

Signed-off-by: Denis Sokolov <[email protected]>

* fix velocity deadband critic tests

Signed-off-by: Denis Sokolov <[email protected]>

---------

Signed-off-by: Denis Sokolov <[email protected]>

* removing clearable layer param (unused) (#4280)

* provide message validation check API (#4276)

* provide validation_message.hpp

Signed-off-by: goes <[email protected]>

* fix typo

Signed-off-by: goes <[email protected]>

* add test_validation_messages.cpp

Signed-off-by: goes <[email protected]>

* change include-order

Signed-off-by: goes <[email protected]>

* reformat

Signed-off-by: goes <[email protected]>

* update test

Signed-off-by: goes <[email protected]>

---------

Signed-off-by: goes <[email protected]>
Co-authored-by: goes <[email protected]>

* Add footprint clearing for static layer (#4282)

* Add footprint clearing for static layer

Signed-off-by: Tony Najjar <[email protected]>

* fix flckering

---------

Signed-off-by: Tony Najjar <[email protected]>

* Fix #4268 (#4296)

Signed-off-by: Steve Macenski <[email protected]>

* Update README.md of nav2_bt_navigator (#4309)

Update link to docs

Signed-off-by: João Britto <[email protected]>

* Fix undefined symbols in `libpf_lib.so` (#4312)

When I build `nav2_amcl` with `-Wl,--no-undefined` I noticed
`libpf_lib.so` has undefined symbols. This PR correctly links
`libpf_lib.so` to `libm` so all symbols can be found.

You can verify this by executing the following command:
```
ldd -r ./build/nav2_amcl/src/pf/libpf_lib.so
	linux-vdso.so.1 (0x00007ffd1f8c0000)
	libc.so.6 => /lib/x86_64-linux-gnu/libc.so.6 (0x000074e909a00000)
	/lib64/ld-linux-x86-64.so.2 (0x000074e909e60000)
undefined symbol: ceil	(./build/nav2_amcl/src/pf/libpf_lib.so)
undefined symbol: atan2	(./build/nav2_amcl/src/pf/libpf_lib.so)
undefined symbol: sin	(./build/nav2_amcl/src/pf/libpf_lib.so)
undefined symbol: hypot	(./build/nav2_amcl/src/pf/libpf_lib.so)
undefined symbol: cos	(./build/nav2_amcl/src/pf/libpf_lib.so)
undefined symbol: log	(./build/nav2_amcl/src/pf/libpf_lib.so)
undefined symbol: sqrt	(./build/nav2_amcl/src/pf/libpf_lib.so)
undefined symbol: floor	(./build/nav2_amcl/src/pf/libpf_lib.so)
```

Signed-off-by: Ramon Wijnands <[email protected]>

* msg validation check for `/initialpose`  in `nav2_amcl` (#4301)

* add validation check for PoseWithCovarianceStamped

Signed-off-by: goes <[email protected]>

* remove rebundant check before

Signed-off-by: goes <[email protected]>

* reformat

Signed-off-by: goes <[email protected]>

* typo fixed

Signed-off-by: goes <[email protected]>

* change the type-name

Signed-off-by: goes <[email protected]>

* update test

Signed-off-by: goes <[email protected]>

* reformat

Signed-off-by: goes <[email protected]>

* .

Signed-off-by: goes <[email protected]>

* add comment

Signed-off-by: goes <[email protected]>

* update comment

Signed-off-by: goes <[email protected]>

* change header

Signed-off-by: goes <[email protected]>

* update test

Signed-off-by: goes <[email protected]>

* typo fixed

Signed-off-by: goes <[email protected]>

---------

Signed-off-by: goes <[email protected]>
Co-authored-by: goes <[email protected]>

* 4320: Changed precision of calculations of the HybridNode MotionTable::getClosestAngularBin. (#4324)

Signed-off-by: Krzysztof Pawełczyk <[email protected]>
Co-authored-by: Krzysztof Pawełczyk <[email protected]>

* [LifecycleNode] add bond_heartbeat_period (#4342)

* add bond_heartbeat_period


Signed-off-by: Guillaume Doisy <[email protected]>

* lint

Signed-off-by: Guillaume Doisy <[email protected]>

---------

Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>

* Update path_longer_on_approach.cpp (#4344)

Fix the bug that isPathUpdated function will return false for the reason that it compare the timestaped between new path and old path's last pose

Signed-off-by: StetroF <[email protected]>

* [LifecycleManagerClient] clean set_initial_pose and navigate_to_pose (#4346)

Signed-off-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>

* Move projectState after getPointsInside (#4356)

* Modify test to check fix

Signed-off-by: Brice <[email protected]>

* Add static polygon check before simulation

Signed-off-by: Brice <[email protected]>

---------

Signed-off-by: Brice <[email protected]>

* adding final pose in analytic expansion to check (#4353)

* fix sync merge conflicts

* bump humble to 1.1.15 for release

* Revert "[LifecycleNode] add bond_heartbeat_period (#4342)"

This reverts commit 6e44178.

---------

Signed-off-by: pepisg <[email protected]>
Signed-off-by: Wiktor Bajor <[email protected]>
Signed-off-by: Denis Sokolov <[email protected]>
Signed-off-by: goes <[email protected]>
Signed-off-by: Tony Najjar <[email protected]>
Signed-off-by: Steve Macenski <[email protected]>
Signed-off-by: João Britto <[email protected]>
Signed-off-by: Ramon Wijnands <[email protected]>
Signed-off-by: Krzysztof Pawełczyk <[email protected]>
Signed-off-by: Guillaume Doisy <[email protected]>
Signed-off-by: StetroF <[email protected]>
Signed-off-by: Brice <[email protected]>
Co-authored-by: Pedro Alejandro González <[email protected]>
Co-authored-by: Wiktor Bajor <[email protected]>
Co-authored-by: Sokolov Denis <[email protected]>
Co-authored-by: GoesM <[email protected]>
Co-authored-by: goes <[email protected]>
Co-authored-by: Tony Najjar <[email protected]>
Co-authored-by: João Britto <[email protected]>
Co-authored-by: Ramon Wijnands <[email protected]>
Co-authored-by: AzaelCicero <[email protected]>
Co-authored-by: Krzysztof Pawełczyk <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: Guillaume Doisy <[email protected]>
Co-authored-by: StetroF <[email protected]>
Co-authored-by: BriceRenaudeau <[email protected]>
  • Loading branch information
15 people committed May 23, 2024
1 parent 8f097af commit 6cee761
Show file tree
Hide file tree
Showing 68 changed files with 969 additions and 78 deletions.
2 changes: 1 addition & 1 deletion nav2_amcl/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_amcl</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>
<p>
amcl is a probabilistic localization system for a robot moving in
Expand Down
12 changes: 7 additions & 5 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@
#pragma GCC diagnostic pop

#include "nav2_amcl/portable_utils.hpp"
#include "nav2_util/validate_messages.hpp"

using namespace std::placeholders;
using rcl_interfaces::msg::ParameterType;
Expand Down Expand Up @@ -523,11 +524,8 @@ AmclNode::initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::Sha

RCLCPP_INFO(get_logger(), "initialPoseReceived");

if (msg->header.frame_id == "") {
// This should be removed at some point
RCLCPP_WARN(
get_logger(),
"Received initial pose with empty frame_id. You should always supply a frame_id.");
if (!nav2_util::validateMsg(*msg)) {
RCLCPP_ERROR(get_logger(), "Received initialpose message is malformed. Rejecting.");
return;
}
if (nav2_util::strip_leading_slash(msg->header.frame_id) != global_frame_id_) {
Expand Down Expand Up @@ -1381,6 +1379,10 @@ void
AmclNode::mapReceived(const nav_msgs::msg::OccupancyGrid::SharedPtr msg)
{
RCLCPP_DEBUG(get_logger(), "AmclNode: A new map was received.");
if (!nav2_util::validateMsg(*msg)) {
RCLCPP_ERROR(get_logger(), "Received map message is malformed. Rejecting.");
return;
}
if (first_map_only_ && first_map_received_) {
return;
}
Expand Down
1 change: 1 addition & 0 deletions nav2_amcl/src/pf/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ target_include_directories(pf_lib PRIVATE ../include)
if(HAVE_DRAND48)
target_compile_definitions(pf_lib PRIVATE "HAVE_DRAND48")
endif()
target_link_libraries(pf_lib m)

install(TARGETS
pf_lib
Expand Down
2 changes: 1 addition & 1 deletion nav2_behavior_tree/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_behavior_tree</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>TODO</description>
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
<maintainer email="[email protected]">Carlos Orduno</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ bool PathLongerOnApproach::isPathUpdated(
{
return new_path != old_path && old_path.poses.size() != 0 &&
new_path.poses.size() != 0 &&
old_path.poses.back() == new_path.poses.back();
old_path.poses.back().pose == new_path.poses.back().pose;
}

bool PathLongerOnApproach::isRobotInGoalProximity(
Expand Down
2 changes: 1 addition & 1 deletion nav2_behaviors/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_behaviors</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>TODO</description>
<maintainer email="[email protected]">Carlos Orduno</maintainer>
<maintainer email="[email protected]">Steve Macenski</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_bringup/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_bringup</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>Bringup scripts and configurations for the Nav2 stack</description>
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
<maintainer email="[email protected]">Steve Macenski</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_bt_navigator/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

The BT Navigator (Behavior Tree Navigator) module implements the NavigateToPose and NavigateThroughPoses task interfaces. It is a [Behavior Tree](https://github.com/BehaviorTree/BehaviorTree.CPP/blob/master/docs/BT_basics.md)-based implementation of navigation that is intended to allow for flexibility in the navigation task and provide a way to easily specify complex robot behaviors.

See its [Configuration Guide Page](https://navigation.ros.org/configuration/packages/configuring-bt-navigator.html) for additional parameter descriptions, as well as the [Nav2 Behavior Tree Explanation](https://navigation.ros.org/behavior_trees/index.html) pages explaining more context on the default behavior trees and examples provided in this package.
See its [Configuration Guide Page](https://docs.nav2.org/configuration/packages/configuring-bt-navigator.html) for additional parameter descriptions, as well as the [Nav2 Behavior Tree Explanation](https://docs.nav2.org/behavior_trees/index.html) pages explaining more context on the default behavior trees and examples provided in this package.

## Overview

Expand Down
2 changes: 1 addition & 1 deletion nav2_bt_navigator/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_bt_navigator</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>TODO</description>
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_collision_monitor/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_collision_monitor</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>Collision Monitor</description>
<maintainer email="[email protected]">Alexey Merzlyakov</maintainer>
<maintainer email="[email protected]">Steve Macenski</maintainer>
Expand Down
7 changes: 6 additions & 1 deletion nav2_collision_monitor/src/polygon.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,12 @@ double Polygon::getCollisionTime(
Velocity vel = velocity;

// Array of points transformed to the frame concerned with pose on each simulation step
std::vector<Point> points_transformed;
std::vector<Point> points_transformed = collision_points;

// Check static polygon
if (getPointsInside(points_transformed) >= max_points_) {
return 0.0;
}

// Robot movement simulation
for (double time = 0.0; time <= time_before_collision_; time += simulation_time_step_) {
Expand Down
3 changes: 2 additions & 1 deletion nav2_collision_monitor/test/collision_monitor_node_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -645,7 +645,8 @@ TEST_F(Tester, testProcessApproach)
// 3. Obstacle is inside robot footprint
publishScan(0.5, curr_time);
ASSERT_TRUE(waitData(0.5, 500ms, curr_time));
publishCmdVel(0.5, 0.2, 0.0);
// Publish impossible cmd_vel to ensure robot footprint is checked
publishCmdVel(1000000000.0, 0.2, 0.0);
ASSERT_TRUE(waitCmdVel(500ms));
ASSERT_NEAR(cmd_vel_out_->linear.x, 0.0, EPSILON);
ASSERT_NEAR(cmd_vel_out_->linear.y, 0.0, EPSILON);
Expand Down
2 changes: 1 addition & 1 deletion nav2_common/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_common</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>Common support functionality used throughout the navigation 2 stack</description>
<maintainer email="[email protected]">Carl Delsey</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_constrained_smoother/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_constrained_smoother</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>Ceres constrained smoother</description>
<maintainer email="[email protected]">Matej Vargovcik</maintainer>
<maintainer email="[email protected]">Steve Macenski</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion nav2_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_controller</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>Controller action interface</description>
<maintainer email="[email protected]">Carl Delsey</maintainer>
<license>Apache-2.0</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_core</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>A set of headers for plugins core to the Nav2 stack</description>
<maintainer email="[email protected]">Steve Macenski</maintainer>
<maintainer email="[email protected]">Carl Delsey</maintainer>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,6 @@ class ClearCostmapService

// Clearing parameters
unsigned char reset_value_;
std::vector<std::string> clearable_layers_;

// Server for clearing the costmap
rclcpp::Service<nav2_msgs::srv::ClearCostmapExceptRegion>::SharedPtr clear_except_service_;
Expand Down
12 changes: 12 additions & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,7 @@
#include "nav2_costmap_2d/layered_costmap.hpp"
#include "nav_msgs/msg/occupancy_grid.hpp"
#include "rclcpp/rclcpp.hpp"
#include "nav2_costmap_2d/footprint.hpp"

namespace nav2_costmap_2d
{
Expand Down Expand Up @@ -160,6 +161,17 @@ class StaticLayer : public CostmapLayer
rcl_interfaces::msg::SetParametersResult
dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);

std::vector<geometry_msgs::msg::Point> transformed_footprint_;
bool footprint_clearing_enabled_;
/**
* @brief Clear costmap layer info below the robot's footprint
*/
void updateFootprint(
double robot_x, double robot_y, double robot_yaw, double * min_x,
double * min_y,
double * max_x,
double * max_y);

std::string global_frame_; ///< @brief The global frame for the costmap
std::string map_frame_; /// @brief frame that map is located in

Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format ="3">
<name>nav2_costmap_2d</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>
This package provides an implementation of a 2D costmap that takes in sensor
data from the world, builds a 2D or 3D occupancy grid of the data (depending
Expand Down
35 changes: 34 additions & 1 deletion nav2_costmap_2d/plugins/static_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@
#include "pluginlib/class_list_macros.hpp"
#include "tf2/convert.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "nav2_util/validate_messages.hpp"

PLUGINLIB_EXPORT_CLASS(nav2_costmap_2d::StaticLayer, nav2_costmap_2d::Layer)

Expand Down Expand Up @@ -132,6 +133,7 @@ StaticLayer::getParameters()
declareParameter("map_subscribe_transient_local", rclcpp::ParameterValue(true));
declareParameter("transform_tolerance", rclcpp::ParameterValue(0.0));
declareParameter("map_topic", rclcpp::ParameterValue(""));
declareParameter("footprint_clearing_enabled", rclcpp::ParameterValue(false));

auto node = node_.lock();
if (!node) {
Expand All @@ -140,6 +142,7 @@ StaticLayer::getParameters()

node->get_parameter(name_ + "." + "enabled", enabled_);
node->get_parameter(name_ + "." + "subscribe_to_updates", subscribe_to_updates_);
node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_);
std::string private_map_topic, global_map_topic;
node->get_parameter(name_ + "." + "map_topic", private_map_topic);
node->get_parameter("map_topic", global_map_topic);
Expand Down Expand Up @@ -277,6 +280,10 @@ StaticLayer::interpretValue(unsigned char value)
void
StaticLayer::incomingMap(const nav_msgs::msg::OccupancyGrid::SharedPtr new_map)
{
if (!nav2_util::validateMsg(*new_map)) {
RCLCPP_ERROR(logger_, "Received map message is malformed. Rejecting.");
return;
}
if (!map_received_) {
processMap(*new_map);
map_received_ = true;
Expand Down Expand Up @@ -328,7 +335,7 @@ StaticLayer::incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr u

void
StaticLayer::updateBounds(
double /*robot_x*/, double /*robot_y*/, double /*robot_yaw*/, double * min_x,
double robot_x, double robot_y, double robot_yaw, double * min_x,
double * min_y,
double * max_x,
double * max_y)
Expand Down Expand Up @@ -366,6 +373,24 @@ StaticLayer::updateBounds(
*max_y = std::max(wy, *max_y);

has_updated_data_ = false;

updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
}

void
StaticLayer::updateFootprint(
double robot_x, double robot_y, double robot_yaw,
double * min_x, double * min_y,
double * max_x,
double * max_y)
{
if (!footprint_clearing_enabled_) {return;}

transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_);

for (unsigned int i = 0; i < transformed_footprint_.size(); i++) {
touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
}
}

void
Expand All @@ -387,6 +412,10 @@ StaticLayer::updateCosts(
return;
}

if (footprint_clearing_enabled_) {
setConvexPolygonCost(transformed_footprint_, nav2_costmap_2d::FREE_SPACE);
}

if (!layered_costmap_->isRolling()) {
// if not rolling, the layered costmap (master_grid) has same coordinates as this layer
if (!use_maximum_) {
Expand Down Expand Up @@ -469,6 +498,10 @@ StaticLayer::dynamicParametersCallback(
has_updated_data_ = true;
current_ = false;
}
} else if (param_type == ParameterType::PARAMETER_BOOL) {
if (param_name == name_ + "." + "footprint_clearing_enabled") {
footprint_clearing_enabled_ = parameter.as_bool();
}
}
}
result.successful = true;
Expand Down
2 changes: 0 additions & 2 deletions nav2_costmap_2d/src/clear_costmap_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,8 +40,6 @@ ClearCostmapService::ClearCostmapService(
logger_ = node->get_logger();
reset_value_ = costmap_.getCostmap()->getDefaultValue();

node->get_parameter("clearable_layers", clearable_layers_);

clear_except_service_ = node->create_service<ClearExceptRegion>(
"clear_except_" + costmap_.getName(),
std::bind(
Expand Down
3 changes: 0 additions & 3 deletions nav2_costmap_2d/src/costmap_2d_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -85,8 +85,6 @@ Costmap2DROS::Costmap2DROS(
{
RCLCPP_INFO(get_logger(), "Creating Costmap");

std::vector<std::string> clearable_layers{"obstacle_layer", "voxel_layer", "range_layer"};

declare_parameter("always_send_full_costmap", rclcpp::ParameterValue(false));
declare_parameter("footprint_padding", rclcpp::ParameterValue(0.01f));
declare_parameter("footprint", rclcpp::ParameterValue(std::string("[]")));
Expand All @@ -113,7 +111,6 @@ Costmap2DROS::Costmap2DROS(
declare_parameter("unknown_cost_value", rclcpp::ParameterValue(static_cast<unsigned char>(0xff)));
declare_parameter("update_frequency", rclcpp::ParameterValue(5.0));
declare_parameter("use_maximum", rclcpp::ParameterValue(false));
declare_parameter("clearable_layers", rclcpp::ParameterValue(clearable_layers));
}

Costmap2DROS::~Costmap2DROS()
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/costmap_queue/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>costmap_queue</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>The costmap_queue package</description>
<maintainer email="[email protected]">David V. Lu!!</maintainer>
<license>BSD-3-Clause</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/dwb_core/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>dwb_core</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>TODO</description>
<maintainer email="[email protected]">Carl Delsey</maintainer>
<license>BSD-3-Clause</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/dwb_critics/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>dwb_critics</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>The dwb_critics package</description>
<maintainer email="[email protected]">David V. Lu!!</maintainer>
<license>BSD-3-Clause</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/dwb_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>dwb_msgs</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>Message/Service definitions specifically for the dwb_core</description>
<maintainer email="[email protected]">David V. Lu!!</maintainer>
<license>BSD-3-Clause</license>
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/dwb_plugins/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>dwb_plugins</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>
Standard implementations of the GoalChecker
and TrajectoryGenerators for dwb_core
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/nav2_dwb_controller/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav2_dwb_controller</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>
ROS2 controller (DWB) metapackage
</description>
Expand Down
2 changes: 1 addition & 1 deletion nav2_dwb_controller/nav_2d_msgs/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>nav_2d_msgs</name>
<version>1.1.14</version>
<version>1.1.15</version>
<description>Basic message types for two dimensional navigation, extending from geometry_msgs::Pose2D.</description>
<maintainer email="[email protected]">David V. Lu!!</maintainer>
<license>BSD-3-Clause</license>
Expand Down
Loading

0 comments on commit 6cee761

Please sign in to comment.