Skip to content

Commit ddd1b4d

Browse files
SteveMacenskiGoesMgoesgennartanjoaobrittoneto
authored
Iron Sync 8: August 23, 2024 (#4645)
* earlier `executor_thread_.reset()` in nav2_costmap_ros (#4385) * reorder cleanup_queue Signed-off-by: goes <[email protected]> * codestyle Signed-off-by: goes <[email protected]> * codestyle Signed-off-by: goes <[email protected]> --------- Signed-off-by: goes <[email protected]> Co-authored-by: goes <[email protected]> * [RotationShimController] Fix test for rotate to goal heading (#4289) (#4391) * Fix rotate to goal heading tests Signed-off-by: Antoine Gennart <[email protected]> * Update bt_service_node.hpp debug msg (#4398) Provide service_name instead of service_node_name for debugging bt_service_node Signed-off-by: João Britto <[email protected]> * reset laser_scan_filter before reinit (#4397) Signed-off-by: goes <[email protected]> Co-authored-by: goes <[email protected]> * Fix error messages (#4411) Signed-off-by: Christoph Froehlich <[email protected]> * Warn if inflation_radius_ < inscribed_radius_ (#4423) * Warn if inflation_radius_ < inscribed_radius_ Signed-off-by: Tony Najjar <[email protected]> * convert to error Signed-off-by: Tony Najjar <[email protected]> --------- Signed-off-by: Tony Najjar <[email protected]> * chore: cleanup ros1 leftovers (#4446) Signed-off-by: Rein Appeldoorn <[email protected]> * precomputeDistanceHeuristic is now computed once (#4451) Signed-off-by: Vincent Belpois <[email protected]> Co-authored-by: SiddharthaUpase <[email protected]> * shutdown services in destructor of `ClearCostmapService` (#4495) Signed-off-by: GoesM_server <[email protected]> Co-authored-by: GoesM_server <[email protected]> * Fix world to map coordinate conversion (#4506) Signed-off-by: HovorunBh <[email protected]> * fix(nav2_costmap_2d): make obstacle layer not current on enabled toggle (#4507) Signed-off-by: Kemal Bektas <[email protected]> Co-authored-by: Kemal Bektas <[email protected]> * min_turning_r_ getting param fix (#4510) * min_turning_r_ getting param fix Signed-off-by: Ivan Radionov <[email protected]> * Update nav2_mppi_controller/include/nav2_mppi_controller/motion_models.hpp Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: Ivan Radionov <[email protected]> --------- Signed-off-by: Ivan Radionov <[email protected]> Signed-off-by: Steve Macenski <[email protected]> Co-authored-by: Ivan Radionov <[email protected]> Co-authored-by: Steve Macenski <[email protected]> * Return out of map update if frames mismatch. Signed-off-by Joey Yang (#4517) Signed-off-by: Joey Yang <[email protected]> * check nullptr in smoothPlan() (#4544) * check nullptr in smoothPlan() Signed-off-by: GoesM <[email protected]> * code-style Signed-off-by: GoesM <[email protected]> * code-style Signed-off-by: GoesM <[email protected]> * simple change Signed-off-by: GoesM <[email protected]> --------- Signed-off-by: GoesM <[email protected]> Co-authored-by: GoesM <[email protected]> * check nullPtr in `computeControl()` (#4548) Signed-off-by: goes <[email protected]> Co-authored-by: goes <[email protected]> * bumping to 1.2.10 for release * fixing merge conflict iron --------- Signed-off-by: goes <[email protected]> Signed-off-by: Antoine Gennart <[email protected]> Signed-off-by: João Britto <[email protected]> Signed-off-by: Christoph Froehlich <[email protected]> Signed-off-by: Tony Najjar <[email protected]> Signed-off-by: Rein Appeldoorn <[email protected]> Signed-off-by: Vincent Belpois <[email protected]> Signed-off-by: GoesM_server <[email protected]> Signed-off-by: HovorunBh <[email protected]> Signed-off-by: Kemal Bektas <[email protected]> Signed-off-by: Ivan Radionov <[email protected]> Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: Joey Yang <[email protected]> Signed-off-by: GoesM <[email protected]> Co-authored-by: GoesM <[email protected]> Co-authored-by: goes <[email protected]> Co-authored-by: Saitama <[email protected]> Co-authored-by: João Britto <[email protected]> Co-authored-by: Christoph Fröhlich <[email protected]> Co-authored-by: Tony Najjar <[email protected]> Co-authored-by: Rein Appeldoorn <[email protected]> Co-authored-by: Vincent <[email protected]> Co-authored-by: SiddharthaUpase <[email protected]> Co-authored-by: Bohdan <[email protected]> Co-authored-by: Kemal Bektas <[email protected]> Co-authored-by: Kemal Bektas <[email protected]> Co-authored-by: Ivan Radionov <[email protected]> Co-authored-by: Ivan Radionov <[email protected]> Co-authored-by: Joey Yang <[email protected]>
1 parent 09f6572 commit ddd1b4d

File tree

67 files changed

+128
-249
lines changed

Some content is hidden

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

67 files changed

+128
-249
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.9</version>
5+
<version>1.2.10</version>
66
<description>
77
<p>
88
amcl is a probabilistic localization system for a robot moving in

nav2_amcl/src/amcl_node.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -1367,6 +1367,7 @@ AmclNode::dynamicParametersCallback(
13671367
lasers_update_.clear();
13681368
frame_to_laser_.clear();
13691369
laser_scan_connection_.disconnect();
1370+
laser_scan_filter_.reset();
13701371
laser_scan_sub_.reset();
13711372

13721373
initMessageFilters();

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -100,7 +100,7 @@ class BtActionNode : public BT::ActionNodeBase
100100
RCLCPP_DEBUG(node_->get_logger(), "Waiting for \"%s\" action server", action_name.c_str());
101101
if (!action_client_->wait_for_action_server(wait_for_service_timeout_)) {
102102
RCLCPP_ERROR(
103-
node_->get_logger(), "\"%s\" action server not available after waiting for %f s",
103+
node_->get_logger(), "\"%s\" action server not available after waiting for %.2fs",
104104
action_name.c_str(),
105105
wait_for_service_timeout_.count() / 1000.0);
106106
throw std::runtime_error(

nav2_behavior_tree/include/nav2_behavior_tree/bt_cancel_action_node.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -93,8 +93,8 @@ class BtCancelActionNode : public BT::ActionNodeBase
9393
RCLCPP_DEBUG(node_->get_logger(), "Waiting for \"%s\" action server", action_name.c_str());
9494
if (!action_client_->wait_for_action_server(wait_for_service_timeout_)) {
9595
RCLCPP_ERROR(
96-
node_->get_logger(), "\"%s\" action server not available after waiting for 1 s",
97-
action_name.c_str());
96+
node_->get_logger(), "\"%s\" action server not available after waiting for %.2fs",
97+
action_name.c_str(), wait_for_service_timeout_.count() / 1000.0);
9898
throw std::runtime_error(
9999
std::string("Action server ") + action_name +
100100
std::string(" not available"));

nav2_behavior_tree/include/nav2_behavior_tree/bt_service_node.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -84,12 +84,12 @@ class BtServiceNode : public BT::ActionNodeBase
8484
service_name_.c_str());
8585
if (!service_client_->wait_for_service(wait_for_service_timeout_)) {
8686
RCLCPP_ERROR(
87-
node_->get_logger(), "\"%s\" service server not available after waiting for 1 s",
88-
service_node_name.c_str());
87+
node_->get_logger(), "\"%s\" service server not available after waiting for %.2fs",
88+
service_name_.c_str(), wait_for_service_timeout_.count() / 1000.0);
8989
throw std::runtime_error(
9090
std::string(
9191
"Service server %s not available",
92-
service_node_name.c_str()));
92+
service_name_.c_str()));
9393
}
9494

9595
RCLCPP_DEBUG(

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.9</version>
5+
<version>1.2.10</version>
66
<description>TODO</description>
77
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
88
<maintainer email="[email protected]">Carlos Orduno</maintainer>

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.9</version>
5+
<version>1.2.10</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.9</version>
5+
<version>1.2.10</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.9</version>
5+
<version>1.2.10</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.9</version>
5+
<version>1.2.10</version>
66
<description>Collision Monitor</description>
77
<maintainer email="[email protected]">Alexey Merzlyakov</maintainer>
88
<maintainer email="[email protected]">Steve Macenski</maintainer>

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.9</version>
5+
<version>1.2.10</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.9</version>
5+
<version>1.2.10</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.9</version>
5+
<version>1.2.10</version>
66
<description>Controller action interface</description>
77
<maintainer email="[email protected]">Carl Delsey</maintainer>
88
<license>Apache-2.0</license>

nav2_controller/src/controller_server.cpp

+9-4
Original file line numberDiff line numberDiff line change
@@ -436,31 +436,36 @@ void ControllerServer::computeControl()
436436
RCLCPP_INFO(get_logger(), "Received a goal, begin computing control effort.");
437437

438438
try {
439-
std::string c_name = action_server_->get_current_goal()->controller_id;
439+
auto goal = action_server_->get_current_goal();
440+
if (!goal) {
441+
return; // goal would be nullptr if action_server_ is inactivate.
442+
}
443+
444+
std::string c_name = goal->controller_id;
440445
std::string current_controller;
441446
if (findControllerId(c_name, current_controller)) {
442447
current_controller_ = current_controller;
443448
} else {
444449
throw nav2_core::InvalidController("Failed to find controller name: " + c_name);
445450
}
446451

447-
std::string gc_name = action_server_->get_current_goal()->goal_checker_id;
452+
std::string gc_name = goal->goal_checker_id;
448453
std::string current_goal_checker;
449454
if (findGoalCheckerId(gc_name, current_goal_checker)) {
450455
current_goal_checker_ = current_goal_checker;
451456
} else {
452457
throw nav2_core::ControllerException("Failed to find goal checker name: " + gc_name);
453458
}
454459

455-
std::string pc_name = action_server_->get_current_goal()->progress_checker_id;
460+
std::string pc_name = goal->progress_checker_id;
456461
std::string current_progress_checker;
457462
if (findProgressCheckerId(pc_name, current_progress_checker)) {
458463
current_progress_checker_ = current_progress_checker;
459464
} else {
460465
throw nav2_core::ControllerException("Failed to find progress checker name: " + pc_name);
461466
}
462467

463-
setPlannerPath(action_server_->get_current_goal()->path);
468+
setPlannerPath(goal->path);
464469
progress_checkers_[current_progress_checker_]->reset();
465470

466471
last_valid_cmd_time_ = now();

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.9</version>
5+
<version>1.2.10</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/cfg/Costmap2D.cfg

-23
This file was deleted.

nav2_costmap_2d/cfg/GenericPlugin.cfg

-7
This file was deleted.

nav2_costmap_2d/cfg/InflationPlugin.cfg

-12
This file was deleted.

nav2_costmap_2d/cfg/ObstaclePlugin.cfg

-22
This file was deleted.

nav2_costmap_2d/cfg/VoxelPlugin.cfg

-22
This file was deleted.

nav2_costmap_2d/include/nav2_costmap_2d/clear_costmap_service.hpp

+5
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,11 @@ class ClearCostmapService
4848
*/
4949
ClearCostmapService() = delete;
5050

51+
/**
52+
* @brief A destructor
53+
*/
54+
~ClearCostmapService();
55+
5156
/**
5257
* @brief Clears the region outside of a user-specified area reverting to the static map
5358
*/

nav2_costmap_2d/launch/example.launch

-21
This file was deleted.

nav2_costmap_2d/launch/example_params.yaml

-43
This file was deleted.

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.9</version>
5+
<version>1.2.10</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/inflation_layer.cpp

+10
Original file line numberDiff line numberDiff line change
@@ -170,6 +170,16 @@ InflationLayer::onFootprintChanged()
170170
computeCaches();
171171
need_reinflation_ = true;
172172

173+
if (inflation_radius_ < inscribed_radius_) {
174+
RCLCPP_ERROR(
175+
logger_,
176+
"The configured inflation radius (%.3f) is smaller than "
177+
"the computed inscribed radius (%.3f) of your footprint, "
178+
"it is highly recommended to set inflation radius to be at "
179+
"least as big as the inscribed radius to avoid collisions",
180+
inflation_radius_, inscribed_radius_);
181+
}
182+
173183
RCLCPP_DEBUG(
174184
logger_, "InflationLayer::onFootprintChanged(): num footprint points: %zu,"
175185
" inscribed_radius_ = %.3f, inflation_radius_ = %.3f",

nav2_costmap_2d/plugins/obstacle_layer.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -304,8 +304,11 @@ ObstacleLayer::dynamicParametersCallback(
304304
max_obstacle_height_ = parameter.as_double();
305305
}
306306
} else if (param_type == ParameterType::PARAMETER_BOOL) {
307-
if (param_name == name_ + "." + "enabled") {
307+
if (param_name == name_ + "." + "enabled" && enabled_ != parameter.as_bool()) {
308308
enabled_ = parameter.as_bool();
309+
if (enabled_) {
310+
current_ = false;
311+
}
309312
} else if (param_name == name_ + "." + "footprint_clearing_enabled") {
310313
footprint_clearing_enabled_ = parameter.as_bool();
311314
}

nav2_costmap_2d/plugins/static_layer.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -318,6 +318,7 @@ StaticLayer::incomingUpdate(map_msgs::msg::OccupancyGridUpdate::ConstSharedPtr u
318318
"StaticLayer: Map update ignored. Current map is in frame %s "
319319
"but update was in frame %s",
320320
map_frame_.c_str(), update->header.frame_id.c_str());
321+
return;
321322
}
322323

323324
unsigned int di = 0;

0 commit comments

Comments
 (0)