Skip to content

Commit db46198

Browse files
authored
refactor(autoware_lanelet2_utils): rewrite using modern C++ without API breakage (#347)
* refactor using modern c++ Signed-off-by: Yutaka Kondo <yutaka.kondo@youtalk.jp> * precommit Signed-off-by: Yutaka Kondo <yutaka.kondo@youtalk.jp> * fix Signed-off-by: Yutaka Kondo <yutaka.kondo@youtalk.jp> * fix Signed-off-by: Yutaka Kondo <yutaka.kondo@youtalk.jp> * precommit Signed-off-by: Yutaka Kondo <yutaka.kondo@youtalk.jp> * use std::strcmp Signed-off-by: Yutaka Kondo <yutaka.kondo@youtalk.jp> * precommit Signed-off-by: Yutaka Kondo <yutaka.kondo@youtalk.jp> * Revert "refactor using modern c++" This reverts commit 3f7e495. --------- Signed-off-by: Yutaka Kondo <yutaka.kondo@youtalk.jp>
1 parent 017b6fd commit db46198

File tree

2 files changed

+9
-7
lines changed

2 files changed

+9
-7
lines changed

Diff for: common/autoware_lanelet2_utils/src/intersection.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
#include <lanelet2_core/primitives/Lanelet.h>
1818

19+
#include <cstring>
1920
namespace autoware::lanelet2_utils
2021
{
2122

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

2728
bool is_straight_direction(const lanelet::ConstLanelet & lanelet)
2829
{
29-
return strcmp(lanelet.attributeOr(k_turn_direction, "else"), k_turn_direction_straight) == 0;
30+
return std::strcmp(lanelet.attributeOr(k_turn_direction, "else"), k_turn_direction_straight) == 0;
3031
}
3132

3233
bool is_left_direction(const lanelet::ConstLanelet & lanelet)
3334
{
34-
return strcmp(lanelet.attributeOr(k_turn_direction, "else"), k_turn_direction_left) == 0;
35+
return std::strcmp(lanelet.attributeOr(k_turn_direction, "else"), k_turn_direction_left) == 0;
3536
}
3637

3738
bool is_right_direction(const lanelet::ConstLanelet & lanelet)
3839
{
39-
return strcmp(lanelet.attributeOr(k_turn_direction, "else"), k_turn_direction_right) == 0;
40+
return std::strcmp(lanelet.attributeOr(k_turn_direction, "else"), k_turn_direction_right) == 0;
4041
}
4142

4243
std::optional<TurnDirection> get_turn_direction(const lanelet::ConstLanelet & lanelet)

Diff for: common/autoware_lanelet2_utils/src/kind.cpp

+5-4
Original file line numberDiff line numberDiff line change
@@ -16,23 +16,24 @@
1616

1717
#include <lanelet2_core/primitives/Lanelet.h>
1818

19+
#include <cstring>
1920
namespace autoware::lanelet2_utils
2021
{
2122
bool is_road_lane(const lanelet::ConstLanelet & lanelet)
2223
{
23-
return strcmp(lanelet.attributeOr(lanelet::AttributeName::Subtype, "none"), k_road_lane_type) ==
24-
0;
24+
return std::strcmp(
25+
lanelet.attributeOr(lanelet::AttributeName::Subtype, "none"), k_road_lane_type) == 0;
2526
}
2627

2728
bool is_shoulder_lane(const lanelet::ConstLanelet & lanelet)
2829
{
29-
return strcmp(
30+
return std::strcmp(
3031
lanelet.attributeOr(lanelet::AttributeName::Subtype, "none"), k_shoulder_lane_type) == 0;
3132
}
3233

3334
bool is_bicycle_lane(const lanelet::ConstLanelet & lanelet)
3435
{
35-
return strcmp(
36+
return std::strcmp(
3637
lanelet.attributeOr(lanelet::AttributeName::Subtype, "none"), k_bicycle_lane_type) == 0;
3738
}
3839
} // namespace autoware::lanelet2_utils

0 commit comments

Comments
 (0)