Skip to content

Commit

Permalink
feat!: replace HADMap with Lanelet (autowarefoundation#133)
Browse files Browse the repository at this point in the history
* feat!: replace HADMap with Lanelet

Signed-off-by: kosuke55 <[email protected]>

* add autoware_msgs to build depends

Signed-off-by: kosuke55 <[email protected]>

Signed-off-by: kosuke55 <[email protected]>
  • Loading branch information
kosuke55 authored Nov 30, 2022
1 parent fb0b014 commit 4c47db4
Show file tree
Hide file tree
Showing 5 changed files with 17 additions and 12 deletions.
4 changes: 4 additions & 0 deletions build_depends.repos
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,7 @@ repositories:
type: git
url: https://github.com/tier4/autoware_auto_msgs.git
version: tier4/main
tmp/autoware_msgs:
type: git
url: https://github.com/autowarefoundation/autoware_msgs.git
version: main
Original file line number Diff line number Diff line change
Expand Up @@ -21,14 +21,14 @@
#include <rclcpp/rclcpp.hpp>

#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
#include <autoware_auto_planning_msgs/msg/had_map_route.hpp>
#include <autoware_planning_msgs/msg/lanelet_route.hpp>

namespace lanelet::utils::route
{
using autoware_auto_mapping_msgs::msg::HADMapBin;
using autoware_auto_planning_msgs::msg::HADMapRoute;
using autoware_planning_msgs::msg::LaneletRoute;

bool isRouteValid(const HADMapRoute & route, const lanelet::LaneletMapPtr lanelet_map_ptr_);
bool isRouteValid(const LaneletRoute & route, const lanelet::LaneletMapPtr lanelet_map_ptr_);
} // namespace lanelet::utils::route

// NOLINTEND(readability-identifier-naming)
Expand Down
2 changes: 1 addition & 1 deletion tmp/lanelet2_extension/lib/route_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@
namespace lanelet::utils
{
bool route::isRouteValid(
const HADMapRoute & route_msg, const lanelet::LaneletMapPtr lanelet_map_ptr_)
const LaneletRoute & route_msg, const lanelet::LaneletMapPtr lanelet_map_ptr_)
{
for (const auto & route_section : route_msg.segments) {
for (const auto & primitive : route_section.primitives) {
Expand Down
1 change: 1 addition & 0 deletions tmp/lanelet2_extension/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@

<depend>autoware_auto_mapping_msgs</depend>
<depend>autoware_auto_planning_msgs</depend>
<depend>autoware_planning_msgs</depend>
<depend>autoware_utils</depend>
<depend>geographiclib</depend>
<depend>geometry_msgs</depend>
Expand Down
16 changes: 8 additions & 8 deletions tmp/lanelet2_extension/test/src/test_route_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include "lanelet2_extension/utility/route_checker.hpp"

#include <autoware_auto_mapping_msgs/msg/had_map_bin.hpp>
#include <autoware_auto_planning_msgs/msg/had_map_route.hpp>
#include <autoware_planning_msgs/msg/lanelet_route.hpp>

#include <gtest/gtest.h>

Expand Down Expand Up @@ -48,9 +48,9 @@ class TestSuite : public ::testing::Test // NOLINT for gtest
sample_map_ptr->add(lanelet);

// create sample routes
autoware_auto_mapping_msgs::msg::MapPrimitive map_primitive;
autoware_auto_mapping_msgs::msg::HADMapSegment map_segment1;
autoware_auto_mapping_msgs::msg::HADMapSegment map_segment2;
autoware_planning_msgs::msg::LaneletPrimitive map_primitive;
autoware_planning_msgs::msg::LaneletSegment map_segment1;
autoware_planning_msgs::msg::LaneletSegment map_segment2;

for (size_t i = 0; i < 2; i++) {
map_primitive.id = lanelet.id();
Expand All @@ -65,8 +65,8 @@ class TestSuite : public ::testing::Test // NOLINT for gtest
~TestSuite() override = default;

lanelet::LaneletMapPtr sample_map_ptr;
autoware_auto_planning_msgs::msg::HADMapRoute sample_route1; // valid route
autoware_auto_planning_msgs::msg::HADMapRoute sample_route2; // invalid route
autoware_planning_msgs::msg::LaneletRoute sample_route1; // valid route
autoware_planning_msgs::msg::LaneletRoute sample_route2; // invalid route

private:
};
Expand All @@ -76,9 +76,9 @@ TEST_F(TestSuite, isRouteValid) // NOLINT for gtest
autoware_auto_mapping_msgs::msg::HADMapBin bin_msg;

const auto route_ptr1 =
std::make_shared<autoware_auto_planning_msgs::msg::HADMapRoute>(sample_route1);
std::make_shared<autoware_planning_msgs::msg::LaneletRoute>(sample_route1);
const auto route_ptr2 =
std::make_shared<autoware_auto_planning_msgs::msg::HADMapRoute>(sample_route2);
std::make_shared<autoware_planning_msgs::msg::LaneletRoute>(sample_route2);

// toBinMsg is tested at test_message_conversion.cpp
lanelet::utils::conversion::toBinMsg(sample_map_ptr, &bin_msg);
Expand Down

0 comments on commit 4c47db4

Please sign in to comment.