Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
46 commits
Select commit Hold shift + click to select a range
0a8307c
Add speed filter zones to depot and warehouse maps. (#5146)
leander-dsouza May 15, 2025
af70b27
suppress rviz logging to warnings and above (#5163)
SteveMacenski May 16, 2025
d7e21cf
Adding Jazzy build job on Main PRs to automatically test Jazzy compat…
SteveMacenski May 16, 2025
0629d5b
Prevent MPPI controller from resetting speed limits upon goal executi…
leander-dsouza May 16, 2025
1addc57
Backward docking without sensors (#5153)
ajtudela May 16, 2025
68c130f
Speed up CI builds for released distros (#5168)
SteveMacenski May 16, 2025
130449d
Save 2 minutes in Main-Jazzy build times to align with other CI job l…
SteveMacenski May 16, 2025
faf189a
Fixing docking server when already docked at the requeste ddock (#5171)
SteveMacenski May 16, 2025
2b679b0
Update mergify.yml
SteveMacenski May 19, 2025
630fd45
fix MPPI goal critic inversion (#5088) (#5105)
brayanpa May 19, 2025
83c9c71
Add stateful to regulated pure pursuit controller (#5167)
jadhm May 19, 2025
8c153ef
tf2 uses hpp headers in rolling (and is backported) (#5180)
Timple May 20, 2025
4783190
added config for laserscan in lb-sim (#5174)
RamanRobotics May 20, 2025
a278acf
Publish planned footprints after smoothing (#5155)
tonynajjar May 20, 2025
6edb7e7
fixing deprecation warning (#5182)
SteveMacenski May 20, 2025
bd8b024
Removing action server timeout duration after fixes to ROS 2, Reverts…
SteveMacenski May 20, 2025
497c65b
action timeout in BT client edits error code and string (#5184)
SteveMacenski May 21, 2025
e89b092
Dynamic Parameters Only validating params that are part of the plugin…
Nils-ChristianIseke May 22, 2025
2eb91b4
Increase Readability of testing. (#5190)
Nils-ChristianIseke May 23, 2025
c2d1c51
Add value rewrites to RewrittenYaml (#5191)
leander-dsouza May 27, 2025
2bbfa85
Updates for Kilted Branch off (#5199)
SteveMacenski May 28, 2025
c0df07e
Removing underlay workspace from Main (#5200)
SteveMacenski May 28, 2025
f50c698
Adding missing dep to loopback sim (#5204)
SteveMacenski May 28, 2025
c94ffa7
Adding parameter warn_when_defaulting_parameters to control default p…
MarcoMatteoBassa May 28, 2025
1f2d1e8
Update mergify.yml
SteveMacenski May 28, 2025
701454f
include bug fix for nav2_smac_planner (#5198)
stevedanomodolor May 28, 2025
c5be373
Revert "Removing underlay workspace from Main" (#5206)
SteveMacenski May 28, 2025
0e2e50e
Option to Reduce Lethal to High-Cost Navigable To Get Out of Keepout …
SteveMacenski Jun 1, 2025
db45206
Prototype solving #5192 Issue 2: Reeds-Shepp reduce small reverse exp…
SteveMacenski Jun 1, 2025
ca2a758
Revert recent smac changes causing regressions (#5221)
SteveMacenski Jun 2, 2025
2fecf06
Disable costmap filter zones from tb3 bringup (only Tb4 enabled) (#5223)
SteveMacenski Jun 2, 2025
bb66f65
Revert "Fix Ci from key signing (#5220)" (#5237)
Nils-ChristianIseke Jun 5, 2025
8febffe
Updating readme table for kilted release (#5249)
SteveMacenski Jun 9, 2025
303fdc7
Add min_distance_to_obstacle parameter to RPP (#4543)
doisyg Jun 10, 2025
b1359aa
Fixing builds for message filters API change while retaining Jazzy, K…
SteveMacenski Jun 11, 2025
aade6e5
Route server corner smoothing (#5226)
alexanderjyuen Jun 12, 2025
30971bc
Conserve curvature with LIMIT action (#5255)
tonynajjar Jun 12, 2025
4c7f8dc
Parametrizing obstacle layer tf filter tolerance (#5261)
MarcoMatteoBassa Jun 12, 2025
2966e34
Add namespace support for rviz costmap cost tool (#5268)
mini-1235 Jun 13, 2025
ec95308
Fix/smac planner orientation goals (#5235)
stevedanomodolor Jun 15, 2025
7369634
Increase cache
SteveMacenski Jun 17, 2025
ce4cd90
fixes for humble main compatibility
SteveMacenski Jun 17, 2025
ac2c4c4
Revert "Removing action server timeout duration after fixes to ROS 2,…
SteveMacenski Jun 17, 2025
0b5b9ff
fixing CI build
SteveMacenski Jun 17, 2025
a9d9ecc
revert
SteveMacenski Jun 17, 2025
34dd2bd
done
SteveMacenski Jun 17, 2025
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions .devcontainer/devcontainer.json
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,8 @@
// "--pid=host", // DDS discovery with host, without --network=host
// "--privileged", // device access to host peripherals, e.g. USB
// "--security-opt=seccomp=unconfined", // enable debugging, e.g. gdb
// "--volume=/tmp/.X11-unix:/tmp/.X11-unix", // X11 socket for GUI applications
// "--gpus=all" // access to all GPUs, e.g. for GPU-accelerated applications
],
"workspaceFolder": "/opt/overlay_ws/src/navigation2",
"workspaceMount": "source=${localWorkspaceFolder},target=${containerWorkspaceFolder},type=bind",
Expand All @@ -23,6 +25,8 @@
"remoteEnv": {
"OVERLAY_MIXINS": "release ccache lld",
"CCACHE_DIR": "/tmp/.ccache"
// "QT_X11_NO_MITSHM": "1", // disable MIT-SHM for X11 forwarding
// "DISPLAY": "${localEnv:DISPLAY}", // X11 forwarding
},
"mounts": [
{
Expand Down
12 changes: 6 additions & 6 deletions .github/mergify.yml
Original file line number Diff line number Diff line change
Expand Up @@ -8,14 +8,14 @@ pull_request_rules:
branches:
- jazzy

- name: backport to iron at reviewers discretion
- name: backport to humble-main at reviewers discretion
conditions:
- base=main
- "label=backport-iron"
- "label=backport-humble-main"
actions:
backport:
branches:
- iron
- humble_main

- name: backport to humble at reviewers discretion
conditions:
Expand All @@ -26,14 +26,14 @@ pull_request_rules:
branches:
- humble

- name: backport to humble_main at reviewers discretion
- name: backport to kilted at reviewers discretion
conditions:
- base=main
- "label=backport-humble-main"
- "label=backport-kilted"
actions:
backport:
branches:
- humble_main
- kilted

- name: delete head branch after merge
conditions:
Expand Down
49 changes: 49 additions & 0 deletions .github/workflows/build_main_against_distros.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
name: Build Against Released Distributions

on:
workflow_dispatch:
pull_request:
branches:
- main

jobs:
build-docker:
runs-on: ubuntu-latest

strategy:
fail-fast: false
matrix:
ros_distro: [jazzy, kilted]

steps:
- name: Checkout repository
uses: actions/checkout@v3

- name: Set up Docker build context
run: |
mkdir -p /tmp/docker_context/ws/src
cp -r . /tmp/docker_context/ws/src
echo 'FROM ghcr.io/ros-navigation/nav2_docker:${{ matrix.ros_distro }}-nightly

RUN apt-get update && apt-get install -y \
python3-pip \
python3-colcon-common-extensions \
python3-vcstool \
git \
curl \
&& rm -rf /var/lib/apt/lists/*

WORKDIR /root/ws

COPY ws /root/ws

RUN apt-get update && rosdep update && \
rosdep install --from-paths src --ignore-src -r -y \
--skip-keys=slam_toolbox

RUN . /opt/ros/${{ matrix.ros_distro }}/setup.sh && colcon build --packages-skip nav2_system_tests nav2_bringup nav2_simple_commander nav2_loopback_sim navigation2' > /tmp/docker_context/Dockerfile


- name: Build Docker image
run: |
docker build -t nav2-${{ matrix.ros_distro }}-main-compatibility /tmp/docker_context
1 change: 1 addition & 0 deletions .github/workflows/update_ci_image.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@ on:
push:
branches:
- main
- kilted
- jazzy
- humble
- humble_main
Expand Down
1 change: 1 addition & 0 deletions .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,7 @@ install
__pycache__/
*.py[cod]
.ipynb_checkpoints
.pytest_cache/

sphinx_doc/_build

Expand Down
73 changes: 37 additions & 36 deletions README.md

Large diffs are not rendered by default.

7 changes: 7 additions & 0 deletions nav2_amcl/include/nav2_amcl/amcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#include <vector>

#include "message_filters/subscriber.hpp"
#include "rclcpp/version.h"

#include "geometry_msgs/msg/pose_stamped.hpp"
#include "nav2_util/lifecycle_node.hpp"
Expand Down Expand Up @@ -171,8 +172,14 @@ class AmclNode : public nav2_util::LifecycleNode
* @brief Initialize incoming data message subscribers and filters
*/
void initMessageFilters();

// To Support Kilted and Older from Message Filters API change
#if RCLCPP_VERSION_GTE(29, 6, 0)
std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan>> laser_scan_sub_;
#else
std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
rclcpp_lifecycle::LifecycleNode>> laser_scan_sub_;
#endif
std::unique_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>> laser_scan_filter_;
message_filters::Connection laser_scan_connection_;

Expand Down
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.3.1</version>
<version>1.4.0</version>
<description>
<p>
amcl is a probabilistic localization system for a robot moving in
Expand Down
9 changes: 9 additions & 0 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1182,6 +1182,9 @@ AmclNode::dynamicParametersCallback(
for (auto parameter : parameters) {
const auto & param_type = parameter.get_type();
const auto & param_name = parameter.get_name();
if (param_name.find('.') != std::string::npos) {
continue;
}

if (param_type == ParameterType::PARAMETER_DOUBLE) {
if (param_name == "alpha1") {
Expand Down Expand Up @@ -1520,9 +1523,15 @@ AmclNode::initMessageFilters()
{
auto sub_opt = rclcpp::SubscriptionOptions();
sub_opt.callback_group = callback_group_;

#if RCLCPP_VERSION_GTE(29, 6, 0)
laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>(
shared_from_this(), scan_topic_, rclcpp::SensorDataQoS(), sub_opt);
#else
laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
rclcpp_lifecycle::LifecycleNode>>(
shared_from_this(), scan_topic_, rmw_qos_profile_sensor_data, sub_opt);
#endif

laser_scan_filter_ = std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
*laser_scan_sub_, *tf_buffer_, odom_frame_id_, 10,
Expand Down
11 changes: 11 additions & 0 deletions nav2_behavior_tree/include/nav2_behavior_tree/bt_action_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -187,6 +187,15 @@ class BtActionNode : public BT::ActionNodeBase
return BT::NodeStatus::SUCCESS;
}

/**
* @brief Function to perform work in a BT Node when the action server times out
* Such as setting the error code ID status to timed out for action clients.
*/
virtual void on_timeout()
{
return;
}

/**
* @brief The main override required by a BT action
* @return BT::NodeStatus Status of tick execution
Expand Down Expand Up @@ -231,6 +240,7 @@ class BtActionNode : public BT::ActionNodeBase
"Timed out while waiting for action server to acknowledge goal request for %s",
action_name_.c_str());
future_goal_handle_.reset();
on_timeout();
return BT::NodeStatus::FAILURE;
}
}
Expand Down Expand Up @@ -261,6 +271,7 @@ class BtActionNode : public BT::ActionNodeBase
"Timed out while waiting for action server to acknowledge goal request for %s",
action_name_.c_str());
future_goal_handle_.reset();
on_timeout();
return BT::NodeStatus::FAILURE;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,12 @@ class AssistedTeleopAction : public BtActionNode<nav2_msgs::action::AssistedTele
*/
BT::NodeStatus on_cancelled() override;

/**
* @brief Function to perform work in a BT Node when the action server times out
* Such as setting the error code ID status to timed out for action clients.
*/
void on_timeout() override;

/**
* @brief Function to read parameters and initialize class variables
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,12 @@ class BackUpAction : public BtActionNode<nav2_msgs::action::BackUp>
*/
BT::NodeStatus on_cancelled() override;

/**
* @brief Function to perform work in a BT Node when the action server times out
* Such as setting the error code ID status to timed out for action clients.
*/
void on_timeout() override;

/**
* @brief Function to read parameters and initialize class variables
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,12 @@ class ComputeAndTrackRouteAction : public BtActionNode<nav2_msgs::action::Comput
*/
BT::NodeStatus on_cancelled() override;

/**
* @brief Function to perform work in a BT Node when the action server times out
* Such as setting the error code ID status to timed out for action clients.
*/
void on_timeout() override;

/**
* @brief Function to perform some user-defined operation after a timeout
* waiting for a result that hasn't been received yet
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,12 @@ class ComputePathThroughPosesAction
*/
BT::NodeStatus on_cancelled() override;

/**
* @brief Function to perform work in a BT Node when the action server times out
* Such as setting the error code ID status to timed out for action clients.
*/
void on_timeout() override;

/**
* \brief Override required by the a BT action. Cancel the action and set the path output
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,12 @@ class ComputePathToPoseAction : public BtActionNode<nav2_msgs::action::ComputePa
*/
BT::NodeStatus on_cancelled() override;

/**
* @brief Function to perform work in a BT Node when the action server times out
* Such as setting the error code ID status to timed out for action clients.
*/
void on_timeout() override;

/**
* \brief Override required by the a BT action. Cancel the action and set the path output
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,12 @@ class ComputeRouteAction : public BtActionNode<nav2_msgs::action::ComputeRoute>
*/
BT::NodeStatus on_cancelled() override;

/**
* @brief Function to perform work in a BT Node when the action server times out
* Such as setting the error code ID status to timed out for action clients.
*/
void on_timeout() override;

/**
* \brief Override required by the a BT action. Cancel the action and set the path output
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,12 @@ class DriveOnHeadingAction : public BtActionNode<nav2_msgs::action::DriveOnHeadi
* @brief Function to perform some user-defined operation upon cancellation of the action
*/
BT::NodeStatus on_cancelled() override;

/**
* @brief Function to perform work in a BT Node when the action server times out
* Such as setting the error code ID status to timed out for action clients.
*/
void on_timeout() override;
};

} // namespace nav2_behavior_tree
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,12 @@ class FollowPathAction : public BtActionNode<nav2_msgs::action::FollowPath>
*/
BT::NodeStatus on_cancelled() override;

/**
* @brief Function to perform work in a BT Node when the action server times out
* Such as setting the error code ID status to timed out for action clients.
*/
void on_timeout() override;

/**
* @brief Function to perform some user-defined operation after a timeout
* waiting for a result that hasn't been received yet
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,12 @@ class NavigateThroughPosesAction : public BtActionNode<nav2_msgs::action::Naviga
*/
BT::NodeStatus on_cancelled() override;

/**
* @brief Function to perform work in a BT Node when the action server times out
* Such as setting the error code ID status to timed out for action clients.
*/
void on_timeout() override;

/**
* @brief Creates list of BT ports
* @return BT::PortsList Containing basic ports along with node-specific ports
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,6 +67,12 @@ class NavigateToPoseAction : public BtActionNode<nav2_msgs::action::NavigateToPo
*/
BT::NodeStatus on_cancelled() override;

/**
* @brief Function to perform work in a BT Node when the action server times out
* Such as setting the error code ID status to timed out for action clients.
*/
void on_timeout() override;

/**
* @brief Creates list of BT ports
* @return BT::PortsList Containing basic ports along with node-specific ports
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,12 @@ class SmoothPathAction : public nav2_behavior_tree::BtActionNode<nav2_msgs::acti
*/
BT::NodeStatus on_cancelled() override;

/**
* @brief Function to perform work in a BT Node when the action server times out
* Such as setting the error code ID status to timed out for action clients.
*/
void on_timeout() override;

/**
* @brief Creates list of BT ports
* @return BT::PortsList Containing basic ports along with node-specific ports
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,12 @@ class SpinAction : public BtActionNode<nav2_msgs::action::Spin>
*/
void on_tick() override;

/**
* @brief Function to perform work in a BT Node when the action server times out
* Such as setting the error code ID status to timed out for action clients.
*/
void on_timeout() override;

/**
* @brief Function to read parameters and initialize class variables
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,6 +50,12 @@ class WaitAction : public BtActionNode<nav2_msgs::action::Wait>
*/
void on_tick() override;

/**
* @brief Function to perform work in a BT Node when the action server times out
* Such as setting the error code ID status to timed out for action clients.
*/
void on_timeout() override;

/**
* @brief Function to read parameters and initialize class variables
*/
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.3.1</version>
<version>1.4.0</version>
<description>Nav2 behavior tree wrappers, nodes, and utilities</description>
<maintainer email="[email protected]">Michael Jeronimo</maintainer>
<maintainer email="[email protected]">Carlos Orduno</maintainer>
Expand Down
Loading