Skip to content

Commit 768947d

Browse files
SteveMacenskitonynajjarcoderbaibaiclaude[bot]ajtudela
authored
Sync Jazzy Aug 19, 2025 1.4.1 (#5469)
* Conserve curvature with LIMIT action (#5255) * Conserve curvature with LIMIT action Signed-off-by: Tony Najjar <[email protected]> * fix format Signed-off-by: Tony Najjar <[email protected]> * fix test Signed-off-by: Tony Najjar <[email protected]> --------- Signed-off-by: Tony Najjar <[email protected]> * Adding epsilon for voxel_layer precision loss (#5314) * Adding epsilon for voxel_layer precision loss Signed-off-by: bhx <[email protected]> * Update nav2_costmap_2d/plugins/voxel_layer.cpp Signed-off-by: Steve Macenski <[email protected]> * Update nav2_costmap_2d/plugins/voxel_layer.cpp Signed-off-by: Steve Macenski <[email protected]> * Update nav2_costmap_2d/plugins/voxel_layer.cpp Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: bhx <[email protected]> Signed-off-by: Steve Macenski <[email protected]> Co-authored-by: Steve Macenski <[email protected]> * fix: correct ThroughActionResult type alias in would_a_planner_recovery_help_condition (#5326) The ThroughActionResult type alias was incorrectly referencing Action::Result instead of ThroughAction::Result, causing the condition to not work properly for ComputePathThroughPoses actions. Fixes #5324 Co-authored-by: claude[bot] <209825114+claude[bot]@users.noreply.github.com> * Adding slow down at target heading to RPP Controller (#5361) * Adding slow down at target heading to RPP Signed-off-by: SteveMacenski <[email protected]> * Update test_regulated_pp.cpp Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: SteveMacenski <[email protected]> Signed-off-by: Steve Macenski <[email protected]> * Eexception rethrow in dockRobot method (#5364) Signed-off-by: Alberto Tudela <[email protected]> * Add global min obstacle height in voxel layer (#5389) * Add min obstacle height in voxel layer Signed-off-by: mini-1235 <[email protected]> * Fix linting Signed-off-by: Maurice <[email protected]> --------- Signed-off-by: mini-1235 <[email protected]> Signed-off-by: Maurice <[email protected]> * [DEX] Enforce 3 digits precision (#5398) Signed-off-by: Guillaume Doisy <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> * [static_layer] limit comparison precision (#5405) * [DEX] limit comparison precision Signed-off-by: Guillaume Doisy <[email protected]> * EPSILON 1e-5 Signed-off-by: Guillaume Doisy <[email protected]> --------- Signed-off-by: Guillaume Doisy <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> * Smooth path even if goal pose is so much near to the robot (#5423) * Smooth path even if goal pose is so much near to the robot Signed-off-by: CihatAltiparmak <[email protected]> * Apply suggestions Signed-off-by: CihatAltiparmak <[email protected]> * Remove unnecessary diff Signed-off-by: CihatAltiparmak <[email protected]> --------- Signed-off-by: CihatAltiparmak <[email protected]> * Fix KeepoutFilter on the ARM architecture (#5436) Signed-off-by: Sushant Chavan <[email protected]> * Fix missing dependency (#5460) * bump to 1.3.8 for Jazzy release Aug 19, 2025 Signed-off-by: SteveMacenski <[email protected]> * load balance CI Signed-off-by: SteveMacenski <[email protected]> --------- Signed-off-by: Tony Najjar <[email protected]> Signed-off-by: bhx <[email protected]> Signed-off-by: Steve Macenski <[email protected]> Signed-off-by: SteveMacenski <[email protected]> Signed-off-by: Alberto Tudela <[email protected]> Signed-off-by: mini-1235 <[email protected]> Signed-off-by: Maurice <[email protected]> Signed-off-by: Guillaume Doisy <[email protected]> Signed-off-by: CihatAltiparmak <[email protected]> Signed-off-by: Sushant Chavan <[email protected]> Co-authored-by: Tony Najjar <[email protected]> Co-authored-by: hutao <[email protected]> Co-authored-by: claude[bot] <209825114+claude[bot]@users.noreply.github.com> Co-authored-by: Alberto Tudela <[email protected]> Co-authored-by: mini-1235 <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> Co-authored-by: Cihat Kurtuluş Altıparmak <[email protected]> Co-authored-by: Sushant Chavan <[email protected]> Co-authored-by: Tim Clephas <[email protected]>
1 parent fcd2975 commit 768947d

File tree

57 files changed

+158
-75
lines changed

Some content is hidden

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

57 files changed

+158
-75
lines changed

.circleci/config.yml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -532,7 +532,7 @@ jobs:
532532

533533
_parameters:
534534
release_parameters: &release_parameters
535-
packages_skip_regex: "nav2_system_tests"
535+
packages_skip_regex: "'(nav2_system_tests|nav2_smac_planner|nav2_mppi_controller|nav2_route|nav2_rviz_plugins|nav2_rotation_shim_controller|nav2_waypoint_follower|nav2_smoother|opennav_docking|nav2_behaviors|nav2_bringup|navigation2)'"
536536

537537
workflows:
538538
version: 2

nav2_amcl/package.xml

Lines changed: 1 addition & 1 deletion
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.3.7</version>
5+
<version>1.3.8</version>
66
<description>
77
<p>
88
amcl is a probabilistic localization system for a robot moving in

nav2_behavior_tree/include/nav2_behavior_tree/plugins/condition/would_a_planner_recovery_help_condition.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ class WouldAPlannerRecoveryHelp : public AreErrorCodesPresent
2929
using Action = nav2_msgs::action::ComputePathToPose;
3030
using ActionResult = Action::Result;
3131
using ThroughAction = nav2_msgs::action::ComputePathThroughPoses;
32-
using ThroughActionResult = Action::Result;
32+
using ThroughActionResult = ThroughAction::Result;
3333

3434
public:
3535
WouldAPlannerRecoveryHelp(

nav2_behavior_tree/package.xml

Lines changed: 1 addition & 1 deletion
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.3.7</version>
5+
<version>1.3.8</version>
66
<description>Nav2 behavior tree wrappers, nodes, and utilities</description>
77
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
88
<maintainer email="[email protected]">Carlos Orduno</maintainer>

nav2_behaviors/package.xml

Lines changed: 1 addition & 1 deletion
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.3.7</version>
5+
<version>1.3.8</version>
66
<description>Nav2 behavior server</description>
77
<maintainer email="[email protected]">Carlos Orduno</maintainer>
88
<maintainer email="[email protected]">Steve Macenski</maintainer>

nav2_bringup/package.xml

Lines changed: 1 addition & 1 deletion
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.3.7</version>
5+
<version>1.3.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

Lines changed: 1 addition & 1 deletion
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.3.7</version>
5+
<version>1.3.8</version>
66
<description>Nav2 BT Navigator Server</description>
77
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
88
<license>Apache-2.0</license>

nav2_collision_monitor/package.xml

Lines changed: 1 addition & 1 deletion
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.3.7</version>
5+
<version>1.3.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/collision_monitor_node.cpp

Lines changed: 9 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -548,13 +548,17 @@ bool CollisionMonitor::processStopSlowdownLimit(
548548
const double linear_vel = std::hypot(velocity.x, velocity.y); // absolute
549549
Velocity safe_vel;
550550
double ratio = 1.0;
551+
552+
// Calculate the most restrictive ratio to preserve curvature
551553
if (linear_vel != 0.0) {
552-
ratio = std::clamp(polygon->getLinearLimit() / linear_vel, 0.0, 1.0);
554+
ratio = std::min(ratio, polygon->getLinearLimit() / linear_vel);
555+
}
556+
if (velocity.tw != 0.0) {
557+
ratio = std::min(ratio, polygon->getAngularLimit() / std::abs(velocity.tw));
553558
}
554-
safe_vel.x = velocity.x * ratio;
555-
safe_vel.y = velocity.y * ratio;
556-
safe_vel.tw = std::clamp(
557-
velocity.tw, -polygon->getAngularLimit(), polygon->getAngularLimit());
559+
ratio = std::clamp(ratio, 0.0, 1.0);
560+
// Apply the same ratio to all components to preserve curvature
561+
safe_vel = velocity * ratio;
558562
// Check that currently calculated velocity is safer than
559563
// chosen for previous shapes one
560564
if (safe_vel < robot_action.req_vel) {

nav2_collision_monitor/test/collision_monitor_node_test.cpp

Lines changed: 8 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -820,10 +820,12 @@ TEST_F(Tester, testProcessStopSlowdownLimit)
820820
publishCmdVel(0.5, 0.2, 0.1);
821821
ASSERT_TRUE(waitCmdVel(500ms));
822822
const double speed = std::sqrt(0.5 * 0.5 + 0.2 * 0.2);
823-
const double ratio = LINEAR_LIMIT / speed;
823+
const double linear_ratio = LINEAR_LIMIT / speed;
824+
const double angular_ratio = ANGULAR_LIMIT / 0.1;
825+
const double ratio = std::min(linear_ratio, angular_ratio);
824826
ASSERT_NEAR(cmd_vel_out_->linear.x, 0.5 * ratio, EPSILON);
825827
ASSERT_NEAR(cmd_vel_out_->linear.y, 0.2 * ratio, EPSILON);
826-
ASSERT_NEAR(cmd_vel_out_->angular.z, 0.09, EPSILON);
828+
ASSERT_NEAR(cmd_vel_out_->angular.z, 0.1 * ratio, EPSILON);
827829
ASSERT_TRUE(waitActionState(500ms));
828830
ASSERT_EQ(action_state_->action_type, LIMIT);
829831
ASSERT_EQ(action_state_->polygon_name, "Limit");
@@ -905,10 +907,12 @@ TEST_F(Tester, testPolygonSource)
905907
publishCmdVel(0.5, 0.2, 0.1);
906908
EXPECT_TRUE(waitCmdVel(500ms));
907909
const double speed = std::sqrt(0.5 * 0.5 + 0.2 * 0.2);
908-
const double ratio = LINEAR_LIMIT / speed;
910+
const double linear_ratio = LINEAR_LIMIT / speed;
911+
const double angular_ratio = ANGULAR_LIMIT / 0.1;
912+
const double ratio = std::min(linear_ratio, angular_ratio);
909913
EXPECT_NEAR(cmd_vel_out_->linear.x, 0.5 * ratio, EPSILON);
910914
EXPECT_NEAR(cmd_vel_out_->linear.y, 0.2 * ratio, EPSILON);
911-
EXPECT_NEAR(cmd_vel_out_->angular.z, 0.09, EPSILON);
915+
EXPECT_NEAR(cmd_vel_out_->angular.z, 0.1 * ratio, EPSILON);
912916
EXPECT_TRUE(waitActionState(500ms));
913917
EXPECT_EQ(action_state_->action_type, LIMIT);
914918
EXPECT_EQ(action_state_->polygon_name, "Limit");

0 commit comments

Comments
 (0)