From 8f256804bbcb5f0c01c8726b31eb945d9395af95 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" <43976882+isamu-takagi@users.noreply.github.com> Date: Wed, 9 Nov 2022 21:48:50 +0900 Subject: [PATCH] feat: apply renaming of vector map route message (#2257) Signed-off-by: Takagi, Isamu Signed-off-by: Takagi, Isamu Signed-off-by: Kotaro Yoshimoto --- .../src/mission_planner/mission_planner.cpp | 8 ++++---- system/default_ad_api/src/utils/route_conversion.cpp | 4 ++-- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/planning/mission_planner/src/mission_planner/mission_planner.cpp b/planning/mission_planner/src/mission_planner/mission_planner.cpp index 16e53e77776b1..6a1c73bfb53c6 100644 --- a/planning/mission_planner/src/mission_planner/mission_planner.cpp +++ b/planning/mission_planner/src/mission_planner/mission_planner.cpp @@ -28,10 +28,10 @@ namespace using autoware_auto_mapping_msgs::msg::HADMapSegment; using autoware_auto_mapping_msgs::msg::MapPrimitive; -using autoware_planning_msgs::msg::VectorMapPrimitive; -using autoware_planning_msgs::msg::VectorMapSegment; +using autoware_planning_msgs::msg::LaneletPrimitive; +using autoware_planning_msgs::msg::LaneletSegment; -MapPrimitive convert(const VectorMapPrimitive & p) +MapPrimitive convert(const LaneletPrimitive & p) { MapPrimitive primitive; primitive.id = p.id; @@ -39,7 +39,7 @@ MapPrimitive convert(const VectorMapPrimitive & p) return primitive; } -HADMapSegment convert(const VectorMapSegment & s) +HADMapSegment convert(const LaneletSegment & s) { HADMapSegment segment; segment.preferred_primitive_id = s.preferred_primitive.id; diff --git a/system/default_ad_api/src/utils/route_conversion.cpp b/system/default_ad_api/src/utils/route_conversion.cpp index 7f0d05183369d..62b7d7fe86a86 100644 --- a/system/default_ad_api/src/utils/route_conversion.cpp +++ b/system/default_ad_api/src/utils/route_conversion.cpp @@ -20,11 +20,11 @@ namespace { using ApiPrimitive = autoware_adapi_v1_msgs::msg::RoutePrimitive; -using MapPrimitive = autoware_planning_msgs::msg::VectorMapPrimitive; +using MapPrimitive = autoware_planning_msgs::msg::LaneletPrimitive; using HadPrimitive = autoware_auto_mapping_msgs::msg::MapPrimitive; using ApiSegment = autoware_adapi_v1_msgs::msg::RouteSegment; +using MapSegment = autoware_planning_msgs::msg::LaneletSegment; using HadSegment = autoware_auto_mapping_msgs::msg::HADMapSegment; -using MapSegment = autoware_planning_msgs::msg::VectorMapSegment; template RetT convert(const ArgT & arg);