diff --git a/common/autoware_interpolation/include/autoware/interpolation/spline_interpolation.hpp b/common/autoware_interpolation/include/autoware/interpolation/spline_interpolation.hpp index f7feada7..b6f5ae3e 100644 --- a/common/autoware_interpolation/include/autoware/interpolation/spline_interpolation.hpp +++ b/common/autoware_interpolation/include/autoware/interpolation/spline_interpolation.hpp @@ -16,7 +16,7 @@ #define AUTOWARE__INTERPOLATION__SPLINE_INTERPOLATION_HPP_ #include "autoware/interpolation/interpolation_utils.hpp" -#include "autoware/universe_utils/geometry/geometry.hpp" +#include "autoware_utils/geometry/geometry.hpp" #include diff --git a/common/autoware_interpolation/include/autoware/interpolation/spline_interpolation_points_2d.hpp b/common/autoware_interpolation/include/autoware/interpolation/spline_interpolation_points_2d.hpp index c9668a4c..68d79cff 100644 --- a/common/autoware_interpolation/include/autoware/interpolation/spline_interpolation_points_2d.hpp +++ b/common/autoware_interpolation/include/autoware/interpolation/spline_interpolation_points_2d.hpp @@ -49,7 +49,7 @@ class SplineInterpolationPoints2d { std::vector points_inner; for (const auto & p : points) { - points_inner.push_back(autoware::universe_utils::getPoint(p)); + points_inner.push_back(autoware_utils::get_point(p)); } calcSplineCoefficientsInner(points_inner); } diff --git a/common/autoware_interpolation/package.xml b/common/autoware_interpolation/package.xml index aa01d82a..a007a4eb 100644 --- a/common/autoware_interpolation/package.xml +++ b/common/autoware_interpolation/package.xml @@ -11,8 +11,8 @@ ament_cmake_auto autoware_cmake - autoware_universe_utils eigen + autoware_utils ament_cmake_ros ament_lint_auto diff --git a/common/autoware_interpolation/src/spline_interpolation_points_2d.cpp b/common/autoware_interpolation/src/spline_interpolation_points_2d.cpp index e0f55cfb..5449fbda 100644 --- a/common/autoware_interpolation/src/spline_interpolation_points_2d.cpp +++ b/common/autoware_interpolation/src/spline_interpolation_points_2d.cpp @@ -90,7 +90,7 @@ geometry_msgs::msg::Pose SplineInterpolationPoints2d::getSplineInterpolatedPose( geometry_msgs::msg::Pose pose; pose.position = getSplineInterpolatedPoint(idx, s); pose.orientation = - autoware::universe_utils::createQuaternionFromYaw(getSplineInterpolatedYaw(idx, s)); + autoware_utils::create_quaternion_from_yaw(getSplineInterpolatedYaw(idx, s)); return pose; } diff --git a/common/autoware_interpolation/test/src/test_spline_interpolation.cpp b/common/autoware_interpolation/test/src/test_spline_interpolation.cpp index 766e94a4..f80c1225 100644 --- a/common/autoware_interpolation/test/src/test_spline_interpolation.cpp +++ b/common/autoware_interpolation/test/src/test_spline_interpolation.cpp @@ -13,7 +13,7 @@ // limitations under the License. #include "autoware/interpolation/spline_interpolation.hpp" -#include "autoware/universe_utils/geometry/geometry.hpp" +#include "autoware_utils/geometry/geometry.hpp" #include diff --git a/common/autoware_interpolation/test/src/test_spline_interpolation_points_2d.cpp b/common/autoware_interpolation/test/src/test_spline_interpolation_points_2d.cpp index 974ad606..a55b7f5d 100644 --- a/common/autoware_interpolation/test/src/test_spline_interpolation_points_2d.cpp +++ b/common/autoware_interpolation/test/src/test_spline_interpolation_points_2d.cpp @@ -14,7 +14,7 @@ #include "autoware/interpolation/spline_interpolation.hpp" #include "autoware/interpolation/spline_interpolation_points_2d.hpp" -#include "autoware/universe_utils/geometry/geometry.hpp" +#include "autoware_utils/geometry/geometry.hpp" #include @@ -27,15 +27,15 @@ using autoware::interpolation::SplineInterpolationPoints2d; TEST(spline_interpolation, splineYawFromPoints) { - using autoware::universe_utils::createPoint; + using autoware_utils::create_point; { // straight std::vector points; - points.push_back(createPoint(0.0, 0.0, 0.0)); - points.push_back(createPoint(1.0, 1.5, 0.0)); - points.push_back(createPoint(2.0, 3.0, 0.0)); - points.push_back(createPoint(3.0, 4.5, 0.0)); - points.push_back(createPoint(4.0, 6.0, 0.0)); + points.push_back(create_point(0.0, 0.0, 0.0)); + points.push_back(create_point(1.0, 1.5, 0.0)); + points.push_back(create_point(2.0, 3.0, 0.0)); + points.push_back(create_point(3.0, 4.5, 0.0)); + points.push_back(create_point(4.0, 6.0, 0.0)); const std::vector ans{0.9827937, 0.9827937, 0.9827937, 0.9827937, 0.9827937}; @@ -47,11 +47,11 @@ TEST(spline_interpolation, splineYawFromPoints) { // curve std::vector points; - points.push_back(createPoint(-2.0, -10.0, 0.0)); - points.push_back(createPoint(2.0, 1.5, 0.0)); - points.push_back(createPoint(3.0, 3.0, 0.0)); - points.push_back(createPoint(5.0, 10.0, 0.0)); - points.push_back(createPoint(10.0, 12.5, 0.0)); + points.push_back(create_point(-2.0, -10.0, 0.0)); + points.push_back(create_point(2.0, 1.5, 0.0)); + points.push_back(create_point(3.0, 3.0, 0.0)); + points.push_back(create_point(5.0, 10.0, 0.0)); + points.push_back(create_point(10.0, 12.5, 0.0)); const std::vector ans{1.368174, 0.961318, 1.086098, 0.938357, 0.278594}; const auto yaws = autoware::interpolation::splineYawFromPoints(points); @@ -62,15 +62,15 @@ TEST(spline_interpolation, splineYawFromPoints) { // size of base_keys is 1 (infeasible to interpolate) std::vector points; - points.push_back(createPoint(1.0, 0.0, 0.0)); + points.push_back(create_point(1.0, 0.0, 0.0)); EXPECT_THROW(autoware::interpolation::splineYawFromPoints(points), std::logic_error); } { // straight: size of base_keys is 2 (edge case in the implementation) std::vector points; - points.push_back(createPoint(1.0, 0.0, 0.0)); - points.push_back(createPoint(2.0, 1.5, 0.0)); + points.push_back(create_point(1.0, 0.0, 0.0)); + points.push_back(create_point(2.0, 1.5, 0.0)); const std::vector ans{0.9827937, 0.9827937}; @@ -82,9 +82,9 @@ TEST(spline_interpolation, splineYawFromPoints) { // straight: size of base_keys is 3 (edge case in the implementation) std::vector points; - points.push_back(createPoint(1.0, 0.0, 0.0)); - points.push_back(createPoint(2.0, 1.5, 0.0)); - points.push_back(createPoint(3.0, 3.0, 0.0)); + points.push_back(create_point(1.0, 0.0, 0.0)); + points.push_back(create_point(2.0, 1.5, 0.0)); + points.push_back(create_point(3.0, 3.0, 0.0)); const std::vector ans{0.9827937, 0.9827937, 0.9827937}; @@ -97,15 +97,15 @@ TEST(spline_interpolation, splineYawFromPoints) TEST(spline_interpolation, SplineInterpolationPoints2d) { - using autoware::universe_utils::createPoint; + using autoware_utils::create_point; // curve std::vector points; - points.push_back(createPoint(-2.0, -10.0, 0.0)); - points.push_back(createPoint(2.0, 1.5, 0.0)); - points.push_back(createPoint(3.0, 3.0, 0.0)); - points.push_back(createPoint(5.0, 10.0, 0.0)); - points.push_back(createPoint(10.0, 12.5, 0.0)); + points.push_back(create_point(-2.0, -10.0, 0.0)); + points.push_back(create_point(2.0, 1.5, 0.0)); + points.push_back(create_point(3.0, 3.0, 0.0)); + points.push_back(create_point(5.0, 10.0, 0.0)); + points.push_back(create_point(10.0, 12.5, 0.0)); SplineInterpolationPoints2d s(points); @@ -194,19 +194,19 @@ TEST(spline_interpolation, SplineInterpolationPoints2d) // size of base_keys is 1 (infeasible to interpolate) std::vector single_points; - single_points.push_back(createPoint(1.0, 0.0, 0.0)); + single_points.push_back(create_point(1.0, 0.0, 0.0)); EXPECT_THROW(SplineInterpolationPoints2d{single_points}, std::logic_error); } TEST(spline_interpolation, SplineInterpolationPoints2dPolymorphism) { - using autoware::universe_utils::createPoint; + using autoware_utils::create_point; using autoware_planning_msgs::msg::TrajectoryPoint; std::vector points; - points.push_back(createPoint(-2.0, -10.0, 0.0)); - points.push_back(createPoint(2.0, 1.5, 0.0)); - points.push_back(createPoint(3.0, 3.0, 0.0)); + points.push_back(create_point(-2.0, -10.0, 0.0)); + points.push_back(create_point(2.0, 1.5, 0.0)); + points.push_back(create_point(3.0, 3.0, 0.0)); std::vector trajectory_points; for (const auto & p : points) {