Skip to content

Commit 0f8fda3

Browse files
SteveMacenskihuiyulhyDreamWestreinzorgennartan
authored
Humble sync 13: Nov 8, 2024 (#4748)
* [DWB] Option to limit velocity commands in trajectory generator (#4663) * Option to limit vel cmd through traj generator Signed-off-by: huiyulhy <[email protected]> * Cleanup Signed-off-by: huiyulhy <[email protected]> * fix linting Signed-off-by: huiyulhy <[email protected]> * Update linting Signed-off-by: huiyulhy <[email protected]> * uncrustify Signed-off-by: huiyulhy <[email protected]> * uncrustify Signed-off-by: huiyulhy <[email protected]> --------- Signed-off-by: huiyulhy <[email protected]> * fix to bt action server logging before bt execution result being ready (#4677) Signed-off-by: DreamWest <[email protected]> * fix(simple-action-server): info log instead of warn on cancel (#4684) Cancelling a goal is nominal behavior and therefore it should not log warning. Signed-off-by: Rein Appeldoorn <[email protected]> * [RotationShimController] fix: rotate to goal heading (#4724) Add frame_id to goal when rotating towards goal heading, otherwise the transform would fail. This bug was introduced in 30e2cde by not setting the frame_id. Signed-off-by: agennart <[email protected]> Co-authored-by: agennart <[email protected]> * Fix incorrect doxygen comment (#4741) Signed-off-by: Ryan Friedman <[email protected]> * [map_io] Replace std logs by rclcpp logs (#4720) * replace std logs by rclcpp logs Signed-off-by: Guillaume Doisy <[email protected]> * RCLCPP_DEBUG to RCLCPP_INFO for visibility Signed-off-by: Guillaume Doisy <[email protected]> --------- Signed-off-by: Guillaume Doisy <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> * bump to 1.1.17 for humble sync Signed-off-by: Steve Macenski <[email protected]> --------- Signed-off-by: huiyulhy <[email protected]> Signed-off-by: DreamWest <[email protected]> Signed-off-by: Rein Appeldoorn <[email protected]> Signed-off-by: agennart <[email protected]> Signed-off-by: Ryan Friedman <[email protected]> Signed-off-by: Guillaume Doisy <[email protected]> Signed-off-by: Steve Macenski <[email protected]> Co-authored-by: Huiyu Leong <[email protected]> Co-authored-by: DreamWest <[email protected]> Co-authored-by: Rein Appeldoorn <[email protected]> Co-authored-by: Saitama <[email protected]> Co-authored-by: agennart <[email protected]> Co-authored-by: Ryan <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]> Co-authored-by: Guillaume Doisy <[email protected]>
1 parent b71caaf commit 0f8fda3

File tree

46 files changed

+145
-108
lines changed

Some content is hidden

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

46 files changed

+145
-108
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.1.16</version>
5+
<version>1.1.17</version>
66
<description>
77
<p>
88
amcl is a probabilistic localization system for a robot moving in

nav2_behavior_tree/include/nav2_behavior_tree/bt_action_server_impl.hpp

+3-3
Original file line numberDiff line numberDiff line change
@@ -260,18 +260,18 @@ void BtActionServer<ActionT>::executeCallback()
260260

261261
switch (rc) {
262262
case nav2_behavior_tree::BtStatus::SUCCEEDED:
263-
RCLCPP_INFO(logger_, "Goal succeeded");
264263
action_server_->succeeded_current(result);
264+
RCLCPP_INFO(logger_, "Goal succeeded");
265265
break;
266266

267267
case nav2_behavior_tree::BtStatus::FAILED:
268-
RCLCPP_ERROR(logger_, "Goal failed");
269268
action_server_->terminate_current(result);
269+
RCLCPP_ERROR(logger_, "Goal failed");
270270
break;
271271

272272
case nav2_behavior_tree::BtStatus::CANCELED:
273-
RCLCPP_INFO(logger_, "Goal canceled");
274273
action_server_->terminate_all(result);
274+
RCLCPP_INFO(logger_, "Goal canceled");
275275
break;
276276
}
277277
}

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.1.16</version>
5+
<version>1.1.17</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.1.16</version>
5+
<version>1.1.17</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.1.16</version>
5+
<version>1.1.17</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.1.16</version>
5+
<version>1.1.17</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.1.16</version>
5+
<version>1.1.17</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.1.16</version>
5+
<version>1.1.17</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.1.16</version>
5+
<version>1.1.17</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.1.16</version>
5+
<version>1.1.17</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.1.16</version>
5+
<version>1.1.17</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/costmap_2d.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -150,8 +150,7 @@ class Costmap2D
150150

151151
/**
152152
* @brief Get the cost of a cell in the costmap
153-
* @param mx The x coordinate of the cell
154-
* @param my The y coordinate of the cell
153+
* @param index The cell index
155154
* @return The cost of the cell
156155
*/
157156
unsigned char getCost(unsigned int index) const;

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.1.16</version>
5+
<version>1.1.17</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_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.1.16</version>
4+
<version>1.1.17</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.1.16</version>
5+
<version>1.1.17</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.1.16</version>
4+
<version>1.1.17</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.1.16</version>
5+
<version>1.1.17</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/include/dwb_plugins/standard_traj_generator.hpp

+3
Original file line numberDiff line numberDiff line change
@@ -147,6 +147,9 @@ class StandardTrajectoryGenerator : public dwb_core::TrajectoryGenerator
147147
/// @brief the name of the overlying plugin ID
148148
std::string plugin_name_;
149149

150+
/// @brief Option to limit velocity in the trajectory generator by using current velocity
151+
bool limit_vel_cmd_in_traj_;
152+
150153
/* Backwards Compatibility Parameter: include_last_point
151154
*
152155
* dwa had an off-by-one error built into it.

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.1.16</version>
4+
<version>1.1.17</version>
55
<description>
66
Standard implementations of the GoalChecker
77
and TrajectoryGenerators for dwb_core

nav2_dwb_controller/dwb_plugins/src/standard_traj_generator.cpp

+10
Original file line numberDiff line numberDiff line change
@@ -75,6 +75,10 @@ void StandardTrajectoryGenerator::initialize(
7575
nh,
7676
plugin_name + ".include_last_point", rclcpp::ParameterValue(true));
7777

78+
nav2_util::declare_parameter_if_not_declared(
79+
nh,
80+
plugin_name + ".limit_vel_cmd_in_traj", rclcpp::ParameterValue(false));
81+
7882
/*
7983
* If discretize_by_time, then sim_granularity represents the amount of time that should be between
8084
* two successive points on the trajectory.
@@ -89,6 +93,7 @@ void StandardTrajectoryGenerator::initialize(
8993
nh->get_parameter(plugin_name + ".linear_granularity", linear_granularity_);
9094
nh->get_parameter(plugin_name + ".angular_granularity", angular_granularity_);
9195
nh->get_parameter(plugin_name + ".include_last_point", include_last_point_);
96+
nh->get_parameter(plugin_name + ".limit_vel_cmd_in_traj", limit_vel_cmd_in_traj_);
9297
}
9398

9499
void StandardTrajectoryGenerator::initializeIterator(
@@ -156,9 +161,14 @@ dwb_msgs::msg::Trajectory2D StandardTrajectoryGenerator::generateTrajectory(
156161
double running_time = 0.0;
157162
std::vector<double> steps = getTimeSteps(cmd_vel);
158163
traj.poses.push_back(start_pose);
164+
bool first_vel = false;
159165
for (double dt : steps) {
160166
// calculate velocities
161167
vel = computeNewVelocity(cmd_vel, vel, dt);
168+
if (!first_vel && limit_vel_cmd_in_traj_) {
169+
traj.velocity = vel;
170+
first_vel = true;
171+
}
162172

163173
// update the position of the robot using the velocities passed in
164174
pose = computeNewPosition(pose, vel, dt);

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.1.16</version>
5+
<version>1.1.17</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.1.16</version>
5+
<version>1.1.17</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.1.16</version>
5+
<version>1.1.17</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>

nav2_graceful_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_graceful_controller</name>
5-
<version>1.1.16</version>
5+
<version>1.1.17</version>
66
<description>Graceful motion controller</description>
77
<maintainer email="[email protected]">Alberto Tudela</maintainer>
88
<license>Apache-2.0</license>

nav2_lifecycle_manager/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_lifecycle_manager</name>
5-
<version>1.1.16</version>
5+
<version>1.1.17</version>
66
<description>A controller/manager for the lifecycle nodes of the Navigation 2 system</description>
77
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
88
<license>Apache-2.0</license>

nav2_map_server/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_map_server</name>
5-
<version>1.1.16</version>
5+
<version>1.1.17</version>
66
<description>
77
Refactored map server for ROS2 Navigation
88
</description>

0 commit comments

Comments
 (0)