Skip to content

Commit aa8fa85

Browse files
committed
rename get_arc_coordinates_on_centerline to get_arc_coordinates
Signed-off-by: Sarun Mukdapitak <sarun.mukda@gmail.com>
1 parent e2532ef commit aa8fa85

3 files changed

Lines changed: 11 additions & 14 deletions

File tree

common/autoware_lanelet2_utils/include/autoware/lanelet2_utils/geometry.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -164,7 +164,7 @@ lanelet::ArcCoordinates get_arc_coordinates(
164164
* @param[in] lanelet_map_ptr LaneletMap
165165
* @return ArcCoordinates of the pose on lanelet sequence
166166
*/
167-
lanelet::ArcCoordinates get_arc_coordinates_on_ego_centerline(
167+
lanelet::ArcCoordinates get_arc_coordinates(
168168
const lanelet::ConstLanelets & lanelets, const geometry_msgs::msg::Pose & pose,
169169
const lanelet::LaneletMapConstPtr & lanelet_map_ptr);
170170

common/autoware_lanelet2_utils/src/geometry.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -413,7 +413,7 @@ lanelet::ArcCoordinates get_arc_coordinates(
413413
return arc_coordinates;
414414
}
415415

416-
lanelet::ArcCoordinates get_arc_coordinates_on_ego_centerline(
416+
lanelet::ArcCoordinates get_arc_coordinates(
417417
const lanelet::ConstLanelets & lanelets, const geometry_msgs::msg::Pose & pose,
418418
const lanelet::LaneletMapConstPtr & lanelet_map_ptr)
419419
{

common/autoware_lanelet2_utils/test/geometry.cpp

Lines changed: 9 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -559,11 +559,10 @@ TEST_F(GetArcCoordinates, get_arc_coordinateEmptyCase)
559559
EXPECT_EQ(arc_coord.length, 0);
560560
EXPECT_EQ(arc_coord.distance, 0);
561561

562-
// get_arc_coordinates_on_ego_centerline should give same result without waypoints
562+
// get_arc_coordinates should give same result without waypoints
563563
{
564-
auto arc_coord_on_ego_centerline =
565-
autoware::experimental::lanelet2_utils::get_arc_coordinates_on_ego_centerline(
566-
empty_lanelet_sequence, query, lanelet_map_ptr_);
564+
auto arc_coord_on_ego_centerline = autoware::experimental::lanelet2_utils::get_arc_coordinates(
565+
empty_lanelet_sequence, query, lanelet_map_ptr_);
567566
EXPECT_EQ(arc_coord_on_ego_centerline.length, 0);
568567
EXPECT_EQ(arc_coord_on_ego_centerline.distance, 0);
569568
}
@@ -603,10 +602,9 @@ TEST_F(GetArcCoordinates, get_arc_coordinateOrdinaryCase)
603602
EXPECT_NEAR(arc_coord.length, 1.5, 1e-4);
604603
EXPECT_NEAR(arc_coord.distance, 0.1, 1e-4);
605604

606-
// get_arc_coordinates_on_ego_centerline should give same result without waypoints
607-
auto arc_coord_on_ego_centerline =
608-
autoware::experimental::lanelet2_utils::get_arc_coordinates_on_ego_centerline(
609-
lanelet_sequence, query, lanelet_map_ptr_);
605+
// get_arc_coordinates should give same result without waypoints
606+
auto arc_coord_on_ego_centerline = autoware::experimental::lanelet2_utils::get_arc_coordinates(
607+
lanelet_sequence, query, lanelet_map_ptr_);
610608
EXPECT_NEAR(arc_coord_on_ego_centerline.length, 1.5, 1e-4);
611609
EXPECT_NEAR(arc_coord_on_ego_centerline.distance, 0.1, 1e-4);
612610
}
@@ -619,10 +617,9 @@ TEST_F(GetArcCoordinates, get_arc_coordinateOrdinaryCase)
619617
EXPECT_NEAR(arc_coord.length, 4.5, 1e-4);
620618
EXPECT_NEAR(arc_coord.distance, -0.1, 1e-4);
621619

622-
// get_arc_coordinates_on_ego_centerline should give same result without waypoints
623-
auto arc_coord_on_ego_centerline =
624-
autoware::experimental::lanelet2_utils::get_arc_coordinates_on_ego_centerline(
625-
lanelet_sequence, query, lanelet_map_ptr_);
620+
// get_arc_coordinates should give same result without waypoints
621+
auto arc_coord_on_ego_centerline = autoware::experimental::lanelet2_utils::get_arc_coordinates(
622+
lanelet_sequence, query, lanelet_map_ptr_);
626623
EXPECT_NEAR(arc_coord_on_ego_centerline.length, 4.5, 1e-4);
627624
EXPECT_NEAR(arc_coord_on_ego_centerline.distance, -0.1, 1e-4);
628625
}

0 commit comments

Comments
 (0)