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 7 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 @@ -34,39 +34,40 @@ enum TurnDirection : int { Straight = 0, Left, Right };
* @param [in] input lanelet
* @return true if and only if the given lanelet has "turn_direction" attribute
*/
bool is_intersection_lanelet(const lanelet::ConstLanelet & lanelet);
[[nodiscard]] bool is_intersection_lanelet(const lanelet::ConstLanelet & lanelet);

/**
* @brief check if given lanelet has "turn_direction" attribute and the value is "straight"
* @param [in] input lanelet
* @return true if and only if the given lanelet has "turn_direction" attribute and the value is
* "straight"
*/
bool is_straight_direction(const lanelet::ConstLanelet & lanelet);
[[nodiscard]] bool is_straight_direction(const lanelet::ConstLanelet & lanelet);

/**
* @brief check if given lanelet has "turn_direction" attribute and the value is "left"
* @param [in] input lanelet
* @return true if and only if the given lanelet has "turn_direction" attribute and the value is
* "left"
*/
bool is_left_direction(const lanelet::ConstLanelet & lanelet);
[[nodiscard]] bool is_left_direction(const lanelet::ConstLanelet & lanelet);

/**
* @brief check if given lanelet has "turn_direction" attribute and the value is "right"
* @param [in] input lanelet
* @return true if and only if the given lanelet has "turn_direction" attribute and the value is
* "right"
*/
bool is_right_direction(const lanelet::ConstLanelet & lanelet);
[[nodiscard]] bool is_right_direction(const lanelet::ConstLanelet & lanelet);

/**
* @brief get the turn_direction value
* @param [in] input lanelet
* @return valid TurnDirection value if `lanelet` has valid "turn_direction" value, otherwise null
* "right"
*/
std::optional<TurnDirection> get_turn_direction(const lanelet::ConstLanelet & lanelet);
[[nodiscard]] std::optional<TurnDirection> get_turn_direction(
const lanelet::ConstLanelet & lanelet);

} // namespace autoware::lanelet2_utils
#endif // AUTOWARE__LANELET2_UTILS__INTERSECTION_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -43,20 +43,20 @@ class BicycleLane : public lanelet::ConstLanelet
* @param [in] lanelet input lanelet
* @return if the lanelet is road or not
*/
bool is_road_lane(const lanelet::ConstLanelet & lanelet);
[[nodiscard]] bool is_road_lane(const lanelet::ConstLanelet & lanelet);

/**
* @brief check if the given lanelet type has "road_shoulder" subtype
* @param [in] lanelet input lanelet
* @return if the lanelet is road_shoulder or not
*/
bool is_shoulder_lane(const lanelet::ConstLanelet & lanelet);
[[nodiscard]] bool is_shoulder_lane(const lanelet::ConstLanelet & lanelet);

/**
* @brief check if the given lanelet type has "bicycle_lane" subtype
* @param [in] lanelet input lanelet
* @return if the lanelet is bicycle_lane or not
*/
bool is_bicycle_lane(const lanelet::ConstLanelet & lanelet);
[[nodiscard]] bool is_bicycle_lane(const lanelet::ConstLanelet & lanelet);
} // namespace autoware::lanelet2_utils
#endif // AUTOWARE__LANELET2_UTILS__KIND_HPP_
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ namespace autoware::lanelet2_utils
* @param participant [in, opt, lanelet::Participants::Vehicle] participant value
* @return RoutingGraph object without road_shoulder and bicycle_lane
*/
lanelet::routing::RoutingGraphConstPtr instantiate_routing_graph(
[[nodiscard]] lanelet::routing::RoutingGraphConstPtr instantiate_routing_graph(
lanelet::LaneletMapConstPtr lanelet_map, const char * location = lanelet::Locations::Germany,
const char * participant = lanelet::Participants::Vehicle);

Expand All @@ -41,7 +41,7 @@ lanelet::routing::RoutingGraphConstPtr instantiate_routing_graph(
* @param [in] routing_graph routing_graph containing `lanelet`
* @return optional of left adjacent lanelet(nullopt if there is no such adjacent lanelet)
*/
std::optional<lanelet::ConstLanelet> left_lanelet(
[[nodiscard]] std::optional<lanelet::ConstLanelet> left_lanelet(
const lanelet::ConstLanelet & lanelet,
const lanelet::routing::RoutingGraphConstPtr routing_graph);

Expand All @@ -51,7 +51,7 @@ std::optional<lanelet::ConstLanelet> left_lanelet(
* @param [in] routing_graph routing_graph containing `lanelet`
* @return optional of right adjacent lanelet(nullopt if there is no such adjacent lanelet)
*/
std::optional<lanelet::ConstLanelet> right_lanelet(
[[nodiscard]] std::optional<lanelet::ConstLanelet> right_lanelet(
const lanelet::ConstLanelet & lanelet,
const lanelet::routing::RoutingGraphConstPtr routing_graph);

Expand Down Expand Up @@ -87,7 +87,7 @@ const lanelet::routing::RoutingGraphConstPtr routing_graph);
* @param [in] lanelet_map lanelet_map containing `lanelet`
* @return optional of the left opposite lanelet(nullopt if there is not such opposite lanelet)
*/
std::optional<lanelet::ConstLanelet> left_opposite_lanelet(
[[nodiscard]] std::optional<lanelet::ConstLanelet> left_opposite_lanelet(
const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map);

/**
Expand All @@ -96,7 +96,7 @@ std::optional<lanelet::ConstLanelet> left_opposite_lanelet(
* @param [in] routing_graph routing_graph containing `lanelet`
* @return optional of the right opposite lanelet(nullopt if there is no such opposite lanelet)
*/
std::optional<lanelet::ConstLanelet> right_opposite_lanelet(
[[nodiscard]] std::optional<lanelet::ConstLanelet> right_opposite_lanelet(
const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map);

/**
Expand All @@ -105,11 +105,11 @@ std::optional<lanelet::ConstLanelet> right_opposite_lanelet(
* @param [in] routing_graph routing_graph containing `lanelet`
* @return optional of such lanelet(nullopt if there is no such adjacent lanelet)
*/
std::optional<lanelet::ConstLanelet> leftmost_lanelet(
[[nodiscard]] std::optional<lanelet::ConstLanelet> leftmost_lanelet(
const lanelet::ConstLanelet & lanelet,
const lanelet::routing::RoutingGraphConstPtr routing_graph);

std::optional<lanelet::ConstLanelet> rightmost_lanelet(
[[nodiscard]] std::optional<lanelet::ConstLanelet> rightmost_lanelet(
const lanelet::ConstLanelet & lanelet,
const lanelet::routing::RoutingGraphConstPtr routing_graph);

Expand All @@ -123,7 +123,7 @@ std::optional<lanelet::ConstLanelet> rightmost_lanelet(
* @return the list of lanelets excluding `lanelet` which is ordered in the *hopping* number from
* `lanelet`
*/
lanelet::ConstLanelets left_lanelets(
[[nodiscard]] lanelet::ConstLanelets left_lanelets(
const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map,
const lanelet::routing::RoutingGraphConstPtr routing_graph, const bool include_opposite = false,
const bool invert_opposite_lane = false);
Expand All @@ -138,7 +138,7 @@ lanelet::ConstLanelets left_lanelets(
* @return the list of lanelets excluding `lanelet` which is ordered in the *hopping* number from
* `lanelet`
*/
lanelet::ConstLanelets right_lanelets(
[[nodiscard]] lanelet::ConstLanelets right_lanelets(
const lanelet::ConstLanelet & lanelet, const lanelet::LaneletMapConstPtr lanelet_map,
const lanelet::routing::RoutingGraphConstPtr routing_graph, const bool include_opposite = false,
const bool invert_opposite_lane = false);
Expand All @@ -149,7 +149,7 @@ lanelet::ConstLanelets right_lanelets(
* @param [in] routing_graph routing_graph containing `lanelet`
* @return the following lanelets
*/
lanelet::ConstLanelets following_lanelets(
[[nodiscard]] lanelet::ConstLanelets following_lanelets(
const lanelet::ConstLanelet & lanelet,
const lanelet::routing::RoutingGraphConstPtr routing_graph);

Expand All @@ -159,7 +159,7 @@ lanelet::ConstLanelets following_lanelets(
* @param [in] routing_graph routing_graph containing `lanelet`
* @return the previous lanelets
*/
lanelet::ConstLanelets previous_lanelets(
[[nodiscard]] lanelet::ConstLanelets previous_lanelets(
const lanelet::ConstLanelet & lanelet,
const lanelet::routing::RoutingGraphConstPtr routing_graph);

Expand All @@ -169,7 +169,7 @@ lanelet::ConstLanelets previous_lanelets(
* @param [in] routing_graph routing_graph containing `lanelet`
* @return the sibling lanelets excluding `lanelet`
*/
lanelet::ConstLanelets sibling_lanelets(
[[nodiscard]] lanelet::ConstLanelets sibling_lanelets(
const lanelet::ConstLanelet & lanelet,
const lanelet::routing::RoutingGraphConstPtr routing_graph);

Expand All @@ -179,7 +179,7 @@ lanelet::ConstLanelets sibling_lanelets(
* @param [in] routing_graph routing_graph containing `lanelet`
* @return the list of Lanelets in the same order as `ids`
*/
lanelet::ConstLanelets from_ids(
[[nodiscard]] lanelet::ConstLanelets from_ids(
const lanelet::LaneletMapConstPtr lanelet_map, const std::vector<lanelet::Id> & ids);
} // namespace autoware::lanelet2_utils

Expand Down
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