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: add the empty route test and empty map test #38

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
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
4 changes: 4 additions & 0 deletions autoware_lanelet2_extension/lib/route_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,10 @@ namespace lanelet::utils
bool route::isRouteValid(
const LaneletRoute & route_msg, const lanelet::LaneletMapPtr lanelet_map_ptr_)
{
if (route_msg.segments.empty()) {
std::cerr << "Route is empty, returning false." << std::endl;
return false;
}
Comment on lines +29 to +32
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Whether an empty route segment is considered invalid is a matter of interpretation.

for (const auto & route_section : route_msg.segments) {
for (const auto & primitive : route_section.primitives) {
const auto id = primitive.id;
Expand Down
18 changes: 18 additions & 0 deletions autoware_lanelet2_extension/test/src/test_route_checker.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -91,6 +91,24 @@ TEST_F(TestSuite, isRouteValid) // NOLINT for gtest
"one";
}

TEST_F(TestSuite, isRouteInvalidWithEmptyRoute) // NOLINT for gtest
{
// create empty route
autoware_planning_msgs::msg::LaneletRoute empty_route;

ASSERT_FALSE(lanelet::utils::route::isRouteValid(empty_route, sample_map_ptr))
<< "The route should be invalid because it is empty.";
}

TEST_F(TestSuite, isRouteInvalidWithEmptyMap) // NOLINT for gtest
{
// create empty map
auto empty_map_ptr = std::make_shared<lanelet::LaneletMap>();

ASSERT_FALSE(lanelet::utils::route::isRouteValid(sample_route1, empty_map_ptr))
<< "The route should be invalid because the map is empty.";
}

int main(int argc, char ** argv)
{
testing::InitGoogleTest(&argc, argv);
Expand Down
Loading