Skip to content

Commit

Permalink
fix(autoware_interpolation): adaption to autoware_utils
Browse files Browse the repository at this point in the history
Signed-off-by: NorahXiong <[email protected]>
  • Loading branch information
NorahXiong committed Jan 17, 2025
1 parent 1b43810 commit 3483c51
Show file tree
Hide file tree
Showing 6 changed files with 34 additions and 34 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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 <Eigen/Core>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ class SplineInterpolationPoints2d
{
std::vector<geometry_msgs::msg::Point> 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);
}
Expand Down
2 changes: 1 addition & 1 deletion common/autoware_interpolation/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,8 @@
<buildtool_depend>ament_cmake_auto</buildtool_depend>
<buildtool_depend>autoware_cmake</buildtool_depend>

<depend>autoware_universe_utils</depend>
<depend>eigen</depend>
<depend>autoware_utils</depend>

<test_depend>ament_cmake_ros</test_depend>
<test_depend>ament_lint_auto</test_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <gtest/gtest.h>

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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 <gtest/gtest.h>

Expand All @@ -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<geometry_msgs::msg::Point> 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<double> ans{0.9827937, 0.9827937, 0.9827937, 0.9827937, 0.9827937};

Expand All @@ -47,11 +47,11 @@ TEST(spline_interpolation, splineYawFromPoints)

{ // curve
std::vector<geometry_msgs::msg::Point> 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<double> ans{1.368174, 0.961318, 1.086098, 0.938357, 0.278594};
const auto yaws = autoware::interpolation::splineYawFromPoints(points);
Expand All @@ -62,15 +62,15 @@ TEST(spline_interpolation, splineYawFromPoints)

{ // size of base_keys is 1 (infeasible to interpolate)
std::vector<geometry_msgs::msg::Point> 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<geometry_msgs::msg::Point> 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<double> ans{0.9827937, 0.9827937};

Expand All @@ -82,9 +82,9 @@ TEST(spline_interpolation, splineYawFromPoints)

{ // straight: size of base_keys is 3 (edge case in the implementation)
std::vector<geometry_msgs::msg::Point> 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<double> ans{0.9827937, 0.9827937, 0.9827937};

Expand All @@ -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<geometry_msgs::msg::Point> 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);

Expand Down Expand Up @@ -194,19 +194,19 @@ TEST(spline_interpolation, SplineInterpolationPoints2d)

// size of base_keys is 1 (infeasible to interpolate)
std::vector<geometry_msgs::msg::Point> 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<geometry_msgs::msg::Point> 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<TrajectoryPoint> trajectory_points;
for (const auto & p : points) {
Expand Down

0 comments on commit 3483c51

Please sign in to comment.