From 16e9957db066e6f2383574d94ead9ac4a596e5a6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Francisco=20Mart=C3=ADn=20Rico?= Date: Tue, 18 Nov 2025 12:43:46 +0100 Subject: [PATCH] Adaptation to EasyNavigation/EasyNavigation#71 MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Francisco Martín Rico --- .../easynav_gridmap_maps_manager/GridmapMapsBuilderNode.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/easynav_gridmap_maps_manager/src/easynav_gridmap_maps_manager/GridmapMapsBuilderNode.cpp b/easynav_gridmap_maps_manager/src/easynav_gridmap_maps_manager/GridmapMapsBuilderNode.cpp index 0bbf8bc..491b474 100644 --- a/easynav_gridmap_maps_manager/src/easynav_gridmap_maps_manager/GridmapMapsBuilderNode.cpp +++ b/easynav_gridmap_maps_manager/src/easynav_gridmap_maps_manager/GridmapMapsBuilderNode.cpp @@ -53,7 +53,7 @@ GridmapMapsBuilderNode::GridmapMapsBuilderNode(const rclcpp::NodeOptions & optio } if (!has_parameter("perception_default_frame")) { - declare_parameter("perception_default_frame", "map_"); + declare_parameter("perception_default_frame", "map"); } pub_ = this->create_publisher( @@ -154,7 +154,7 @@ void GridmapMapsBuilderNode::cycle() auto downsampled_points = PointPerceptionsOpsView(point_perceptions) .downsample(downsample_resolution_) .fuse(perception_default_frame_) - ->as_points(); + .as_points(); if (downsampled_points.empty()) { return;