Skip to content

refactor(autoware_lanelet2_utils): rewrite using modern C++ without API breakage #347

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

Merged
merged 9 commits into from
Apr 1, 2025
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
7 changes: 4 additions & 3 deletions common/autoware_lanelet2_utils/src/intersection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

#include <lanelet2_core/primitives/Lanelet.h>

#include <cstring>
namespace autoware::lanelet2_utils
{

Expand All @@ -26,17 +27,17 @@ bool is_intersection_lanelet(const lanelet::ConstLanelet & lanelet)

bool is_straight_direction(const lanelet::ConstLanelet & lanelet)
{
return strcmp(lanelet.attributeOr(k_turn_direction, "else"), k_turn_direction_straight) == 0;
return std::strcmp(lanelet.attributeOr(k_turn_direction, "else"), k_turn_direction_straight) == 0;
}

bool is_left_direction(const lanelet::ConstLanelet & lanelet)
{
return strcmp(lanelet.attributeOr(k_turn_direction, "else"), k_turn_direction_left) == 0;
return std::strcmp(lanelet.attributeOr(k_turn_direction, "else"), k_turn_direction_left) == 0;
}

bool is_right_direction(const lanelet::ConstLanelet & lanelet)
{
return strcmp(lanelet.attributeOr(k_turn_direction, "else"), k_turn_direction_right) == 0;
return std::strcmp(lanelet.attributeOr(k_turn_direction, "else"), k_turn_direction_right) == 0;
}

std::optional<TurnDirection> get_turn_direction(const lanelet::ConstLanelet & lanelet)
Expand Down
9 changes: 5 additions & 4 deletions common/autoware_lanelet2_utils/src/kind.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,23 +16,24 @@

#include <lanelet2_core/primitives/Lanelet.h>

#include <cstring>
namespace autoware::lanelet2_utils
{
bool is_road_lane(const lanelet::ConstLanelet & lanelet)
{
return strcmp(lanelet.attributeOr(lanelet::AttributeName::Subtype, "none"), k_road_lane_type) ==
0;
return std::strcmp(
lanelet.attributeOr(lanelet::AttributeName::Subtype, "none"), k_road_lane_type) == 0;
}

bool is_shoulder_lane(const lanelet::ConstLanelet & lanelet)
{
return strcmp(
return std::strcmp(
lanelet.attributeOr(lanelet::AttributeName::Subtype, "none"), k_shoulder_lane_type) == 0;
}

bool is_bicycle_lane(const lanelet::ConstLanelet & lanelet)
{
return strcmp(
return std::strcmp(
lanelet.attributeOr(lanelet::AttributeName::Subtype, "none"), k_bicycle_lane_type) == 0;
}
} // namespace autoware::lanelet2_utils
Loading