Skip to content

Commit 4cb6aba

Browse files
SteveMacenskipepisgWiktor-99perchessGoesM
authored
Iron Sync 6: May 23, 2024 (#4366)
* 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]> * [RotationShimController] rotate also on short paths (#4290) When the path is shorter than ´forward_sampling_distance´ the rotatitonShimController would directly give control to the primary controller to navigate to the goal. This would lead to the exact behavior that was tried to be fixed by the rotationShimController: "The result is an awkward, stuttering, or whipping around behavior" [1]. It often resulted in navigation failure. In this case, the controller should try to rotate towards the last point of the path, so that the primary controller can have a better starting orientation. [1] https://navigation.ros.org/tuning/index.html#rotate-in-place-behavior * 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]> * 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) * bump iron to 1.2.8 * fix merge conflict resolution --------- 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: 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: Saitama <[email protected]> Co-authored-by: Tony Najjar <[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]>
1 parent 4e16d3c commit 4cb6aba

File tree

69 files changed

+958
-164
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

69 files changed

+958
-164
lines changed

nav2_amcl/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_amcl</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>
77
<p>
88
amcl is a probabilistic localization system for a robot moving in

nav2_amcl/src/amcl_node.cpp

+7-5
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,7 @@
4949
#pragma GCC diagnostic pop
5050

5151
#include "nav2_amcl/portable_utils.hpp"
52+
#include "nav2_util/validate_messages.hpp"
5253

5354
using namespace std::placeholders;
5455
using rcl_interfaces::msg::ParameterType;
@@ -523,11 +524,8 @@ AmclNode::initialPoseReceived(geometry_msgs::msg::PoseWithCovarianceStamped::Sha
523524

524525
RCLCPP_INFO(get_logger(), "initialPoseReceived");
525526

526-
if (msg->header.frame_id == "") {
527-
// This should be removed at some point
528-
RCLCPP_WARN(
529-
get_logger(),
530-
"Received initial pose with empty frame_id. You should always supply a frame_id.");
527+
if (!nav2_util::validateMsg(*msg)) {
528+
RCLCPP_ERROR(get_logger(), "Received initialpose message is malformed. Rejecting.");
531529
return;
532530
}
533531
if (nav2_util::strip_leading_slash(msg->header.frame_id) != global_frame_id_) {
@@ -1390,6 +1388,10 @@ void
13901388
AmclNode::mapReceived(const nav_msgs::msg::OccupancyGrid::SharedPtr msg)
13911389
{
13921390
RCLCPP_DEBUG(get_logger(), "AmclNode: A new map was received.");
1391+
if (!nav2_util::validateMsg(*msg)) {
1392+
RCLCPP_ERROR(get_logger(), "Received map message is malformed. Rejecting.");
1393+
return;
1394+
}
13931395
if (first_map_only_ && first_map_received_) {
13941396
return;
13951397
}

nav2_amcl/src/pf/CMakeLists.txt

+1
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@ target_include_directories(pf_lib PRIVATE ../include)
1515
if(HAVE_DRAND48)
1616
target_compile_definitions(pf_lib PRIVATE "HAVE_DRAND48")
1717
endif()
18+
target_link_libraries(pf_lib m)
1819

1920
install(TARGETS
2021
pf_lib

nav2_behavior_tree/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_behavior_tree</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>TODO</description>
77
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
88
<maintainer email="[email protected]">Carlos Orduno</maintainer>

nav2_behavior_tree/plugins/decorator/path_longer_on_approach.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -36,7 +36,7 @@ bool PathLongerOnApproach::isPathUpdated(
3636
{
3737
return new_path != old_path && old_path.poses.size() != 0 &&
3838
new_path.poses.size() != 0 &&
39-
old_path.poses.back() == new_path.poses.back();
39+
old_path.poses.back().pose == new_path.poses.back().pose;
4040
}
4141

4242
bool PathLongerOnApproach::isRobotInGoalProximity(

nav2_behaviors/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_behaviors</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>TODO</description>
77
<maintainer email="[email protected]">Carlos Orduno</maintainer>
88
<maintainer email="[email protected]">Steve Macenski</maintainer>

nav2_bringup/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_bringup</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>Bringup scripts and configurations for the Nav2 stack</description>
77
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
88
<maintainer email="[email protected]">Steve Macenski</maintainer>

nav2_bt_navigator/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_bt_navigator</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>TODO</description>
77
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
88
<license>Apache-2.0</license>

nav2_collision_monitor/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_collision_monitor</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>Collision Monitor</description>
77
<maintainer email="[email protected]">Alexey Merzlyakov</maintainer>
88
<maintainer email="[email protected]">Steve Macenski</maintainer>

nav2_collision_monitor/src/polygon.cpp

+6-1
Original file line numberDiff line numberDiff line change
@@ -248,7 +248,12 @@ double Polygon::getCollisionTime(
248248
Velocity vel = velocity;
249249

250250
// Array of points transformed to the frame concerned with pose on each simulation step
251-
std::vector<Point> points_transformed;
251+
std::vector<Point> points_transformed = collision_points;
252+
253+
// Check static polygon
254+
if (getPointsInside(points_transformed) >= min_points_) {
255+
return 0.0;
256+
}
252257

253258
// Robot movement simulation
254259
for (double time = 0.0; time <= time_before_collision_; time += simulation_time_step_) {

nav2_collision_monitor/test/collision_monitor_node_test.cpp

+2-1
Original file line numberDiff line numberDiff line change
@@ -792,7 +792,8 @@ TEST_F(Tester, testProcessApproach)
792792
// 3. Obstacle is inside robot footprint
793793
publishScan(0.5, curr_time);
794794
ASSERT_TRUE(waitData(0.5, 500ms, curr_time));
795-
publishCmdVel(0.5, 0.2, 0.0);
795+
// Publish impossible cmd_vel to ensure robot footprint is checked
796+
publishCmdVel(1000000000.0, 0.2, 0.0);
796797
ASSERT_TRUE(waitCmdVel(500ms));
797798
ASSERT_NEAR(cmd_vel_out_->linear.x, 0.0, EPSILON);
798799
ASSERT_NEAR(cmd_vel_out_->linear.y, 0.0, EPSILON);

nav2_common/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_common</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>Common support functionality used throughout the navigation 2 stack</description>
77
<maintainer email="[email protected]">Carl Delsey</maintainer>
88
<license>Apache-2.0</license>

nav2_constrained_smoother/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_constrained_smoother</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>Ceres constrained smoother</description>
77
<maintainer email="[email protected]">Matej Vargovcik</maintainer>
88
<maintainer email="[email protected]">Steve Macenski</maintainer>

nav2_controller/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_controller</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>Controller action interface</description>
77
<maintainer email="[email protected]">Carl Delsey</maintainer>
88
<license>Apache-2.0</license>

nav2_core/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_core</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>A set of headers for plugins core to the Nav2 stack</description>
77
<maintainer email="[email protected]">Steve Macenski</maintainer>
88
<maintainer email="[email protected]">Carl Delsey</maintainer>

nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,6 @@ class ClearCostmapService
6767

6868
// Clearing parameters
6969
unsigned char reset_value_;
70-
std::vector<std::string> clearable_layers_;
7170

7271
// Server for clearing the costmap
7372
rclcpp::Service<nav2_msgs::srv::ClearCostmapExceptRegion>::SharedPtr clear_except_service_;

nav2_costmap_2d/include/nav2_costmap_2d/static_layer.hpp

+12
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,7 @@
4848
#include "nav2_costmap_2d/layered_costmap.hpp"
4949
#include "nav_msgs/msg/occupancy_grid.hpp"
5050
#include "rclcpp/rclcpp.hpp"
51+
#include "nav2_costmap_2d/footprint.hpp"
5152

5253
namespace nav2_costmap_2d
5354
{
@@ -160,6 +161,17 @@ class StaticLayer : public CostmapLayer
160161
rcl_interfaces::msg::SetParametersResult
161162
dynamicParametersCallback(std::vector<rclcpp::Parameter> parameters);
162163

164+
std::vector<geometry_msgs::msg::Point> transformed_footprint_;
165+
bool footprint_clearing_enabled_;
166+
/**
167+
* @brief Clear costmap layer info below the robot's footprint
168+
*/
169+
void updateFootprint(
170+
double robot_x, double robot_y, double robot_yaw, double * min_x,
171+
double * min_y,
172+
double * max_x,
173+
double * max_y);
174+
163175
std::string global_frame_; ///< @brief The global frame for the costmap
164176
std::string map_frame_; /// @brief frame that map is located in
165177

nav2_costmap_2d/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format ="3">
44
<name>nav2_costmap_2d</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>
77
This package provides an implementation of a 2D costmap that takes in sensor
88
data from the world, builds a 2D or 3D occupancy grid of the data (depending

nav2_costmap_2d/plugins/static_layer.cpp

+34-1
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,7 @@
4545
#include "pluginlib/class_list_macros.hpp"
4646
#include "tf2/convert.h"
4747
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
48+
#include "nav2_util/validate_messages.hpp"
4849

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

@@ -132,6 +133,7 @@ StaticLayer::getParameters()
132133
declareParameter("map_subscribe_transient_local", rclcpp::ParameterValue(true));
133134
declareParameter("transform_tolerance", rclcpp::ParameterValue(0.0));
134135
declareParameter("map_topic", rclcpp::ParameterValue(""));
136+
declareParameter("footprint_clearing_enabled", rclcpp::ParameterValue(false));
135137

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

141143
node->get_parameter(name_ + "." + "enabled", enabled_);
142144
node->get_parameter(name_ + "." + "subscribe_to_updates", subscribe_to_updates_);
145+
node->get_parameter(name_ + "." + "footprint_clearing_enabled", footprint_clearing_enabled_);
143146
std::string private_map_topic, global_map_topic;
144147
node->get_parameter(name_ + "." + "map_topic", private_map_topic);
145148
node->get_parameter("map_topic", global_map_topic);
@@ -277,6 +280,10 @@ StaticLayer::interpretValue(unsigned char value)
277280
void
278281
StaticLayer::incomingMap(const nav_msgs::msg::OccupancyGrid::SharedPtr new_map)
279282
{
283+
if (!nav2_util::validateMsg(*new_map)) {
284+
RCLCPP_ERROR(logger_, "Received map message is malformed. Rejecting.");
285+
return;
286+
}
280287
if (!map_received_) {
281288
processMap(*new_map);
282289
map_received_ = true;
@@ -328,7 +335,7 @@ StaticLayer::incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr u
328335

329336
void
330337
StaticLayer::updateBounds(
331-
double /*robot_x*/, double /*robot_y*/, double /*robot_yaw*/, double * min_x,
338+
double robot_x, double robot_y, double robot_yaw, double * min_x,
332339
double * min_y,
333340
double * max_x,
334341
double * max_y)
@@ -366,6 +373,24 @@ StaticLayer::updateBounds(
366373
*max_y = std::max(wy, *max_y);
367374

368375
has_updated_data_ = false;
376+
377+
updateFootprint(robot_x, robot_y, robot_yaw, min_x, min_y, max_x, max_y);
378+
}
379+
380+
void
381+
StaticLayer::updateFootprint(
382+
double robot_x, double robot_y, double robot_yaw,
383+
double * min_x, double * min_y,
384+
double * max_x,
385+
double * max_y)
386+
{
387+
if (!footprint_clearing_enabled_) {return;}
388+
389+
transformFootprint(robot_x, robot_y, robot_yaw, getFootprint(), transformed_footprint_);
390+
391+
for (unsigned int i = 0; i < transformed_footprint_.size(); i++) {
392+
touch(transformed_footprint_[i].x, transformed_footprint_[i].y, min_x, min_y, max_x, max_y);
393+
}
369394
}
370395

371396
void
@@ -387,6 +412,10 @@ StaticLayer::updateCosts(
387412
return;
388413
}
389414

415+
if (footprint_clearing_enabled_) {
416+
setConvexPolygonCost(transformed_footprint_, nav2_costmap_2d::FREE_SPACE);
417+
}
418+
390419
if (!layered_costmap_->isRolling()) {
391420
// if not rolling, the layered costmap (master_grid) has same coordinates as this layer
392421
if (!use_maximum_) {
@@ -469,6 +498,10 @@ StaticLayer::dynamicParametersCallback(
469498
has_updated_data_ = true;
470499
current_ = false;
471500
}
501+
} else if (param_type == ParameterType::PARAMETER_BOOL) {
502+
if (param_name == name_ + "." + "footprint_clearing_enabled") {
503+
footprint_clearing_enabled_ = parameter.as_bool();
504+
}
472505
}
473506
}
474507
result.successful = true;

nav2_costmap_2d/src/clear_costmap_service.cpp

-2
Original file line numberDiff line numberDiff line change
@@ -40,8 +40,6 @@ ClearCostmapService::ClearCostmapService(
4040
logger_ = node->get_logger();
4141
reset_value_ = costmap_.getCostmap()->getDefaultValue();
4242

43-
node->get_parameter("clearable_layers", clearable_layers_);
44-
4543
clear_except_service_ = node->create_service<ClearExceptRegion>(
4644
"clear_except_" + costmap_.getName(),
4745
std::bind(

nav2_costmap_2d/src/costmap_2d_ros.cpp

-3
Original file line numberDiff line numberDiff line change
@@ -108,8 +108,6 @@ void Costmap2DROS::init()
108108
{
109109
RCLCPP_INFO(get_logger(), "Creating Costmap");
110110

111-
std::vector<std::string> clearable_layers{"obstacle_layer", "voxel_layer", "range_layer"};
112-
113111
declare_parameter("always_send_full_costmap", rclcpp::ParameterValue(false));
114112
declare_parameter("footprint_padding", rclcpp::ParameterValue(0.01f));
115113
declare_parameter("footprint", rclcpp::ParameterValue(std::string("[]")));
@@ -134,7 +132,6 @@ void Costmap2DROS::init()
134132
declare_parameter("unknown_cost_value", rclcpp::ParameterValue(static_cast<unsigned char>(0xff)));
135133
declare_parameter("update_frequency", rclcpp::ParameterValue(5.0));
136134
declare_parameter("use_maximum", rclcpp::ParameterValue(false));
137-
declare_parameter("clearable_layers", rclcpp::ParameterValue(clearable_layers));
138135
}
139136

140137
Costmap2DROS::~Costmap2DROS()

nav2_dwb_controller/costmap_queue/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package format="2">
33
<name>costmap_queue</name>
4-
<version>1.2.7</version>
4+
<version>1.2.8</version>
55
<description>The costmap_queue package</description>
66
<maintainer email="[email protected]">David V. Lu!!</maintainer>
77
<license>BSD-3-Clause</license>

nav2_dwb_controller/dwb_core/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>dwb_core</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>TODO</description>
77
<maintainer email="[email protected]">Carl Delsey</maintainer>
88
<license>BSD-3-Clause</license>

nav2_dwb_controller/dwb_critics/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package format="2">
33
<name>dwb_critics</name>
4-
<version>1.2.7</version>
4+
<version>1.2.8</version>
55
<description>The dwb_critics package</description>
66
<maintainer email="[email protected]">David V. Lu!!</maintainer>
77
<license>BSD-3-Clause</license>

nav2_dwb_controller/dwb_msgs/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>dwb_msgs</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>Message/Service definitions specifically for the dwb_core</description>
77
<maintainer email="[email protected]">David V. Lu!!</maintainer>
88
<license>BSD-3-Clause</license>

nav2_dwb_controller/dwb_plugins/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package format="2">
33
<name>dwb_plugins</name>
4-
<version>1.2.7</version>
4+
<version>1.2.8</version>
55
<description>
66
Standard implementations of the GoalChecker
77
and TrajectoryGenerators for dwb_core

nav2_dwb_controller/nav2_dwb_controller/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav2_dwb_controller</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>
77
ROS2 controller (DWB) metapackage
88
</description>

nav2_dwb_controller/nav_2d_msgs/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav_2d_msgs</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>Basic message types for two dimensional navigation, extending from geometry_msgs::Pose2D.</description>
77
<maintainer email="[email protected]">David V. Lu!!</maintainer>
88
<license>BSD-3-Clause</license>

nav2_dwb_controller/nav_2d_utils/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="3">
44
<name>nav_2d_utils</name>
5-
<version>1.2.7</version>
5+
<version>1.2.8</version>
66
<description>A handful of useful utility functions for nav_2d packages.</description>
77
<maintainer email="[email protected]">David V. Lu!!</maintainer>
88
<license>BSD-3-Clause</license>

0 commit comments

Comments
 (0)