Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat: apply renaming of vector map route message #2257

Merged
Show file tree
Hide file tree
Changes from all commits
Commits
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
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