Skip to content

Commit

Permalink
feat: apply renaming of vector map route message (autowarefoundation#…
Browse files Browse the repository at this point in the history
…2257)

Signed-off-by: Takagi, Isamu <[email protected]>

Signed-off-by: Takagi, Isamu <[email protected]>
Signed-off-by: Kotaro Yoshimoto <[email protected]>
  • Loading branch information
isamu-takagi authored and HansRobo committed Dec 16, 2022
1 parent 8faacc4 commit 8f25680
Show file tree
Hide file tree
Showing 2 changed files with 6 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -28,18 +28,18 @@ 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;
primitive.primitive_type = p.primitive_type;
return primitive;
}

HADMapSegment convert(const VectorMapSegment & s)
HADMapSegment convert(const LaneletSegment & s)
{
HADMapSegment segment;
segment.preferred_primitive_id = s.preferred_primitive.id;
Expand Down
4 changes: 2 additions & 2 deletions system/default_ad_api/src/utils/route_conversion.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 <class RetT, class ArgT>
RetT convert(const ArgT & arg);
Expand Down

0 comments on commit 8f25680

Please sign in to comment.