From 663e786b8cc176378771bd52ccc1de246721350d Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Francisco=20Mart=C3=ADn=20Rico?= Date: Tue, 21 Oct 2025 07:25:35 +0200 Subject: [PATCH 1/5] Fix CI with the correct branch MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Francisco Martín Rico --- .github/workflows/jazzy.yaml | 3 ++- .github/workflows/kilted.yaml | 3 ++- .github/workflows/rolling.yaml | 3 ++- 3 files changed, 6 insertions(+), 3 deletions(-) diff --git a/.github/workflows/jazzy.yaml b/.github/workflows/jazzy.yaml index 2b22efd5..33198952 100644 --- a/.github/workflows/jazzy.yaml +++ b/.github/workflows/jazzy.yaml @@ -19,7 +19,8 @@ jobs: steps: - name: Repo checkout uses: actions/checkout@v4 - + with: + ref: jazzy - name: Setup ROS 2 uses: ros-tooling/setup-ros@0.7.15 with: diff --git a/.github/workflows/kilted.yaml b/.github/workflows/kilted.yaml index efe7a6c7..f699529f 100644 --- a/.github/workflows/kilted.yaml +++ b/.github/workflows/kilted.yaml @@ -19,7 +19,8 @@ jobs: steps: - name: Repo checkout uses: actions/checkout@v4 - + with: + ref: kilted - name: Setup ROS 2 uses: ros-tooling/setup-ros@0.7.15 with: diff --git a/.github/workflows/rolling.yaml b/.github/workflows/rolling.yaml index 698e83e0..30cd778d 100644 --- a/.github/workflows/rolling.yaml +++ b/.github/workflows/rolling.yaml @@ -19,7 +19,8 @@ jobs: steps: - name: Repo checkout uses: actions/checkout@v4 - + with: + ref: rolling - name: Setup ROS 2 uses: ros-tooling/setup-ros@0.7.15 with: From b10a1e6c3d365dcfad5d6862b7babfa7fd2c134e Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Francisco=20Mart=C3=ADn=20Rico?= Date: Wed, 3 Dec 2025 20:33:37 +0100 Subject: [PATCH 2/5] Sync CI MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Francisco Martín Rico --- README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/README.md b/README.md index 5c9b0802..df009e83 100644 --- a/README.md +++ b/README.md @@ -1,9 +1,9 @@ # EasyNav Plugins [![Doxygen Deployment](https://github.com/EasyNavigation/easynav_plugins/actions/workflows/doxygen-doc.yml/badge.svg)](https://github.com/EasyNavigation/easynav_plugins/actions/workflows/doxygen-doc.yml) -[![rolling](https://github.com/EasyNavigation/easynav_plugins/actions/workflows/rolling.yaml/badge.svg)](https://github.com/EasyNavigation/easynav_plugins/actions/workflows/rolling.yaml) -[![kilted](https://github.com/EasyNavigation/easynav_plugins/actions/workflows/kilted.yaml/badge.svg)](https://github.com/EasyNavigation/easynav_plugins/actions/workflows/kilted.yaml) -[![jazzy](https://github.com/EasyNavigation/easynav_plugins/actions/workflows/jazzy.yaml/badge.svg)](https://github.com/EasyNavigation/easynav_plugins/actions/workflows/jazzy.yaml) +[![rolling](https://github.com/EasyNavigation/easynav_plugins/actions/workflows/rolling.yaml/badge.svg?branch=rolling)](https://github.com/EasyNavigation/easynav_plugins/actions/workflows/rolling.yaml) +[![kilted](https://github.com/EasyNavigation/easynav_plugins/actions/workflows/kilted.yaml/badge.svg?branch=kilted)](https://github.com/EasyNavigation/easynav_plugins/actions/workflows/kilted.yaml) +[![jazzy](https://github.com/EasyNavigation/easynav_plugins/actions/workflows/jazzy.yaml/badge.svg?branch=jazzy)](https://github.com/EasyNavigation/easynav_plugins/actions/workflows/jazzy.yaml) ## Description **EasyNav Plugins** provides the official collection of plugins for the [Easy Navigation (EasyNav)](https://github.com/EasyNavigation) framework. From 94e9d86ea7389a8bd9620848c8fb2fb79b1ada5b Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Francisco=20Mart=C3=ADn=20Rico?= Date: Thu, 4 Dec 2025 08:03:41 +0100 Subject: [PATCH 3/5] Sync to current EasyNavigation MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Francisco Martín Rico --- .../src/easynav_mppi_controller/MPPIController.cpp | 4 ++-- .../src/easynav_serest_controller/SerestController.cpp | 4 ++-- .../src/easynav_vff_controller/VffController.cpp | 2 +- .../src/easynav_costmap_localizer/AMCLLocalizer.cpp | 4 ++-- .../src/easynav_simple_localizer/AMCLLocalizer.cpp | 4 ++-- .../easynav_costmap_maps_manager/filters/ObstacleFilter.cpp | 2 +- .../easynav_navmap_maps_manager/filters/InflationFilter.cpp | 1 + .../easynav_navmap_maps_manager/filters/ObstacleFilter.cpp | 2 +- .../easynav_octomap_maps_manager/filters/ObstacleFilter.cpp | 2 +- .../src/easynav_simple_maps_manager/SimpleMapsManager.cpp | 2 +- 10 files changed, 14 insertions(+), 13 deletions(-) diff --git a/controllers/easynav_mppi_controller/src/easynav_mppi_controller/MPPIController.cpp b/controllers/easynav_mppi_controller/src/easynav_mppi_controller/MPPIController.cpp index 2ea5c5b3..8879738f 100644 --- a/controllers/easynav_mppi_controller/src/easynav_mppi_controller/MPPIController.cpp +++ b/controllers/easynav_mppi_controller/src/easynav_mppi_controller/MPPIController.cpp @@ -173,9 +173,9 @@ MPPIController::update_rt(NavState & nav_state) const auto & filtered = PointPerceptionsOpsView(perceptions) .filter({-1.0, -1.0, -1.0}, {1.0, 1.0, 1.0}) .fuse("map") - ->filter({NAN, NAN, 0.1}, {NAN, NAN, NAN}) + .filter({NAN, NAN, 0.1}, {NAN, NAN, NAN}) .collapse({NAN, NAN, 0.1}) - ->downsample(0.1) + .downsample(0.1) .as_points(); if (filtered.empty()) { diff --git a/controllers/easynav_serest_controller/src/easynav_serest_controller/SerestController.cpp b/controllers/easynav_serest_controller/src/easynav_serest_controller/SerestController.cpp index 669a2d2d..e62f5162 100644 --- a/controllers/easynav_serest_controller/src/easynav_serest_controller/SerestController.cpp +++ b/controllers/easynav_serest_controller/src/easynav_serest_controller/SerestController.cpp @@ -304,10 +304,10 @@ SerestController::closest_obstacle_distance( auto fused = PointPerceptionsOpsView(perceptions) .downsample(0.3) .fuse(get_tf_prefix() + "base_link") - ->filter({-dist_search_radius_, -dist_search_radius_, NAN}, + .filter({-dist_search_radius_, -dist_search_radius_, NAN}, {dist_search_radius_, dist_search_radius_, 2.0}) .collapse({NAN, NAN, 0.1}) - ->downsample(0.3) + .downsample(0.3) .as_points(); double min_dist = std::numeric_limits::infinity(); diff --git a/controllers/easynav_vff_controller/src/easynav_vff_controller/VffController.cpp b/controllers/easynav_vff_controller/src/easynav_vff_controller/VffController.cpp index d03189eb..5e5568b5 100644 --- a/controllers/easynav_vff_controller/src/easynav_vff_controller/VffController.cpp +++ b/controllers/easynav_vff_controller/src/easynav_vff_controller/VffController.cpp @@ -264,7 +264,7 @@ void VffController::update_rt(NavState & nav_state) PointPerceptionsOpsView(perceptions) .filter({-10.0, -10.0, -10.0}, {10.0, 10.0, 10.0}) .fuse(get_tf_prefix() + "base_link") - ->filter({obstacle_detection_x_min_, obstacle_detection_y_min_, obstacle_detection_z_min_}, + .filter({obstacle_detection_x_min_, obstacle_detection_y_min_, obstacle_detection_z_min_}, {obstacle_detection_x_max_, obstacle_detection_y_max_, obstacle_detection_z_max_}).as_points(); diff --git a/localizers/easynav_costmap_localizer/src/easynav_costmap_localizer/AMCLLocalizer.cpp b/localizers/easynav_costmap_localizer/src/easynav_costmap_localizer/AMCLLocalizer.cpp index be56dac4..48cd58c1 100644 --- a/localizers/easynav_costmap_localizer/src/easynav_costmap_localizer/AMCLLocalizer.cpp +++ b/localizers/easynav_costmap_localizer/src/easynav_costmap_localizer/AMCLLocalizer.cpp @@ -427,9 +427,9 @@ AMCLLocalizer::correct(NavState & nav_state) const auto & filtered = PointPerceptionsOpsView(perceptions) .downsample(map_static.getResolution()) .fuse(get_tf_prefix() + "base_footprint") - ->filter({NAN, NAN, 0.1}, {NAN, NAN, NAN}) + .filter({NAN, NAN, 0.1}, {NAN, NAN, NAN}) .collapse({NAN, NAN, 0.1}) - ->downsample(map_static.getResolution()) + .downsample(map_static.getResolution()) .as_points(); if (filtered.empty()) { diff --git a/localizers/easynav_simple_localizer/src/easynav_simple_localizer/AMCLLocalizer.cpp b/localizers/easynav_simple_localizer/src/easynav_simple_localizer/AMCLLocalizer.cpp index af398c5b..cc5c05f6 100644 --- a/localizers/easynav_simple_localizer/src/easynav_simple_localizer/AMCLLocalizer.cpp +++ b/localizers/easynav_simple_localizer/src/easynav_simple_localizer/AMCLLocalizer.cpp @@ -390,9 +390,9 @@ void AMCLLocalizer::correct(NavState & nav_state) const auto & filtered = PointPerceptionsOpsView(perceptions) .downsample(map_static.resolution()) .fuse(get_tf_prefix() + "base_footprint") - ->filter({NAN, NAN, 0.1}, {NAN, NAN, NAN}) + .filter({NAN, NAN, 0.1}, {NAN, NAN, NAN}) .collapse({NAN, NAN, 0.1}) - ->downsample(map_static.resolution()) + .downsample(map_static.resolution()) .as_points(); if (filtered.empty()) { diff --git a/maps_managers/easynav_costmap_maps_manager/src/easynav_costmap_maps_manager/filters/ObstacleFilter.cpp b/maps_managers/easynav_costmap_maps_manager/src/easynav_costmap_maps_manager/filters/ObstacleFilter.cpp index f6623a47..9fc6d254 100644 --- a/maps_managers/easynav_costmap_maps_manager/src/easynav_costmap_maps_manager/filters/ObstacleFilter.cpp +++ b/maps_managers/easynav_costmap_maps_manager/src/easynav_costmap_maps_manager/filters/ObstacleFilter.cpp @@ -60,7 +60,7 @@ ObstacleFilter::update(NavState & nav_state) auto fused = PointPerceptionsOpsView(perceptions) .downsample(dynamic_map.getResolution()) .fuse(get_tf_prefix() + "map") - ->filter({NAN, NAN, 0.1}, {NAN, NAN, NAN}) + .filter({NAN, NAN, 0.1}, {NAN, NAN, NAN}) .as_points(); for (const auto & p : fused) { diff --git a/maps_managers/easynav_navmap_maps_manager/src/easynav_navmap_maps_manager/filters/InflationFilter.cpp b/maps_managers/easynav_navmap_maps_manager/src/easynav_navmap_maps_manager/filters/InflationFilter.cpp index 3c023944..4935d8bb 100644 --- a/maps_managers/easynav_navmap_maps_manager/src/easynav_navmap_maps_manager/filters/InflationFilter.cpp +++ b/maps_managers/easynav_navmap_maps_manager/src/easynav_navmap_maps_manager/filters/InflationFilter.cpp @@ -41,6 +41,7 @@ #include #include +#include #include "easynav_common/types/NavState.hpp" #include "easynav_common/types/Perceptions.hpp" diff --git a/maps_managers/easynav_navmap_maps_manager/src/easynav_navmap_maps_manager/filters/ObstacleFilter.cpp b/maps_managers/easynav_navmap_maps_manager/src/easynav_navmap_maps_manager/filters/ObstacleFilter.cpp index faec9835..ffd0838f 100644 --- a/maps_managers/easynav_navmap_maps_manager/src/easynav_navmap_maps_manager/filters/ObstacleFilter.cpp +++ b/maps_managers/easynav_navmap_maps_manager/src/easynav_navmap_maps_manager/filters/ObstacleFilter.cpp @@ -67,7 +67,7 @@ ObstacleFilter::update(::easynav::NavState & nav_state) auto fused = PointPerceptionsOpsView(perceptions) .downsample(get_map_resolution()) .fuse(get_tf_prefix() + "map") - ->filter({NAN, NAN, 0.1}, {NAN, NAN, NAN}) + .filter({NAN, NAN, 0.1}, {NAN, NAN, NAN}) .as_points(); size_t sidx = 0; diff --git a/maps_managers/easynav_octomap_maps_manager/src/easynav_octomap_maps_manager/filters/ObstacleFilter.cpp b/maps_managers/easynav_octomap_maps_manager/src/easynav_octomap_maps_manager/filters/ObstacleFilter.cpp index 8d6671fc..03d82265 100644 --- a/maps_managers/easynav_octomap_maps_manager/src/easynav_octomap_maps_manager/filters/ObstacleFilter.cpp +++ b/maps_managers/easynav_octomap_maps_manager/src/easynav_octomap_maps_manager/filters/ObstacleFilter.cpp @@ -67,7 +67,7 @@ ObstacleFilter::update(::easynav::NavState & nav_state) auto fused = PointPerceptionsOpsView(perceptions) .downsample(get_map_resolution()) .fuse(get_tf_prefix() + "map") - ->filter({NAN, NAN, 0.1}, {NAN, NAN, NAN}) + .filter({NAN, NAN, 0.1}, {NAN, NAN, NAN}) .as_points(); size_t sidx = 0; diff --git a/maps_managers/easynav_simple_maps_manager/src/easynav_simple_maps_manager/SimpleMapsManager.cpp b/maps_managers/easynav_simple_maps_manager/src/easynav_simple_maps_manager/SimpleMapsManager.cpp index 310a2261..410c8a33 100644 --- a/maps_managers/easynav_simple_maps_manager/src/easynav_simple_maps_manager/SimpleMapsManager.cpp +++ b/maps_managers/easynav_simple_maps_manager/src/easynav_simple_maps_manager/SimpleMapsManager.cpp @@ -156,7 +156,7 @@ SimpleMapsManager::update(NavState & nav_state) auto fused = PointPerceptionsOpsView(perceptions) .downsample(dynamic_map_.resolution()) .fuse(get_tf_prefix() + "map") - ->filter({NAN, NAN, 0.1}, {NAN, NAN, NAN}) + .filter({NAN, NAN, 0.1}, {NAN, NAN, NAN}) .as_points(); for (const auto & p : fused) { From 35af9de705188641f7e687e659ae248d63b2b7f7 Mon Sep 17 00:00:00 2001 From: "Juan S. Cely G." Date: Mon, 16 Feb 2026 17:41:57 +0100 Subject: [PATCH 4/5] Fixed CI --- .github/workflows/kilted.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/kilted.yaml b/.github/workflows/kilted.yaml index b16834b7..6d68281e 100644 --- a/.github/workflows/kilted.yaml +++ b/.github/workflows/kilted.yaml @@ -22,7 +22,7 @@ jobs: - name: build and test uses: ros-tooling/action-ros-ci@0.4.5 with: - package-name: easynav_common easynav_controller easynav_core easynav_interfaces easynav_localizer easynav_maps_manager easynav_planner easynav_sensors easynav_support_py easynav_system easynav_tools easynav_bonxai_maps_manager easynav_costmap_common easynav_costmap_localizer easynav_costmap_maps_manager easynav_costmap_planner easynav_gps_localizer easynav_mppi_controller easynav_navmap_localizer easynav_navmap_maps_manager easynav_navmap_planner easynav_serest_controller easynav_simple_common easynav_simple_controller easynav_simple_localizer easynav_simple_maps_manager easynav_simple_planner easynav_vff_controller + package-name: easynav_bonxai_maps_manager easynav_costmap_common easynav_costmap_localizer easynav_costmap_maps_manager easynav_costmap_planner easynav_gps_localizer easynav_mppi_controller easynav_navmap_localizer easynav_navmap_maps_manager easynav_navmap_planner easynav_serest_controller easynav_simple_common easynav_simple_controller easynav_simple_localizer easynav_simple_maps_manager easynav_simple_planner easynav_vff_controller target-ros2-distro: kilted skip-tests: false colcon-defaults: | From 7a58a2535f5562275f2452d9decfd169eb48eea3 Mon Sep 17 00:00:00 2001 From: "Juan S. Cely G." Date: Mon, 16 Feb 2026 17:54:15 +0100 Subject: [PATCH 5/5] Fixed CI --- .github/workflows/kilted_cron.yaml | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/.github/workflows/kilted_cron.yaml b/.github/workflows/kilted_cron.yaml index dc93850f..39a45694 100644 --- a/.github/workflows/kilted_cron.yaml +++ b/.github/workflows/kilted_cron.yaml @@ -18,10 +18,8 @@ jobs: - name: build and test uses: ros-tooling/action-ros-ci@0.4.5 with: - package-name: easynav_common easynav_controller easynav_core easynav_interfaces easynav_localizer easynav_maps_manager easynav_planner easynav_sensors easynav_support_py easynav_system easynav_tools easynav_bonxai_maps_manager easynav_costmap_common easynav_costmap_localizer easynav_costmap_maps_manager easynav_costmap_planner easynav_gps_localizer easynav_mppi_controller easynav_navmap_localizer easynav_navmap_maps_manager easynav_navmap_planner easynav_serest_controller easynav_simple_common easynav_simple_controller easynav_simple_localizer easynav_simple_maps_manager easynav_simple_planner easynav_vff_controller + package-name: easynav_bonxai_maps_manager easynav_costmap_common easynav_costmap_localizer easynav_costmap_maps_manager easynav_costmap_planner easynav_gps_localizer easynav_mppi_controller easynav_navmap_localizer easynav_navmap_maps_manager easynav_navmap_planner easynav_serest_controller easynav_simple_common easynav_simple_controller easynav_simple_localizer easynav_simple_maps_manager easynav_simple_planner easynav_vff_controller target-ros2-distro: kilted - ref: kilted - vcs-repo-file-url: ${GITHUB_WORKSPACE}/.github/thirdparty.repos skip-tests: false colcon-defaults: | {