Skip to content

Commit

Permalink
fix(interpolation): implementation of template function to header (#698)
Browse files Browse the repository at this point in the history
* Add test for polymorphism (expect linking error)

* Move templatized function impl to header
  • Loading branch information
HiroIshida authored Apr 19, 2022
1 parent 106166e commit b2f90a0
Show file tree
Hide file tree
Showing 3 changed files with 53 additions and 19 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,14 @@ class SplineInterpolationPoints2d
SplineInterpolationPoints2d() = default;

template <typename T>
void calcSplineCoefficients(const std::vector<T> & points);
void calcSplineCoefficients(const std::vector<T> & points)
{
std::vector<geometry_msgs::msg::Point> points_inner;
for (const auto & p : points) {
points_inner.push_back(tier4_autoware_utils::getPoint(p));
}
calcSplineCoefficientsInner(points_inner);
}

// TODO(murooka) implement these functions
// std::vector<geometry_msgs::msg::Point> getSplineInterpolatedPoints(const double width);
Expand All @@ -58,6 +65,7 @@ class SplineInterpolationPoints2d
double getAccumulatedLength(const size_t idx) const;

private:
void calcSplineCoefficientsInner(const std::vector<geometry_msgs::msg::Point> & points);
SplineInterpolation slerp_x_;
SplineInterpolation slerp_y_;

Expand Down
36 changes: 18 additions & 18 deletions common/interpolation/src/spline_interpolation_points_2d.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,16 +35,16 @@ std::vector<double> calcEuclidDist(const std::vector<double> & x, const std::vec
return dist_v;
}

template <typename T>
std::array<std::vector<double>, 3> getBaseValues(const std::vector<T> & points)
std::array<std::vector<double>, 3> getBaseValues(
const std::vector<geometry_msgs::msg::Point> & points)
{
// calculate x, y
std::vector<double> base_x;
std::vector<double> base_y;
for (size_t i = 0; i < points.size(); i++) {
const auto & current_pos = tier4_autoware_utils::getPoint(points.at(i));
const auto & current_pos = points.at(i);
if (i > 0) {
const auto & prev_pos = tier4_autoware_utils::getPoint(points.at(i - 1));
const auto & prev_pos = points.at(i - 1);
if (
std::fabs(current_pos.x - prev_pos.x) < 1e-6 &&
std::fabs(current_pos.y - prev_pos.y) < 1e-6) {
Expand Down Expand Up @@ -88,20 +88,6 @@ template std::vector<double> slerpYawFromPoints(
const std::vector<geometry_msgs::msg::Point> & points);
} // namespace interpolation

template <typename T>
void SplineInterpolationPoints2d::calcSplineCoefficients(const std::vector<T> & points)
{
const auto base = getBaseValues(points);

base_s_vec_ = base.at(0);
const auto & base_x_vec = base.at(1);
const auto & base_y_vec = base.at(2);

// calculate spline coefficients
slerp_x_.calcSplineCoefficients(base_s_vec_, base_x_vec);
slerp_y_.calcSplineCoefficients(base_s_vec_, base_y_vec);
}

geometry_msgs::msg::Point SplineInterpolationPoints2d::getSplineInterpolatedPoint(
const size_t idx, const double s) const
{
Expand Down Expand Up @@ -153,3 +139,17 @@ double SplineInterpolationPoints2d::getAccumulatedLength(const size_t idx) const
}
return base_s_vec_.at(idx);
}

void SplineInterpolationPoints2d::calcSplineCoefficientsInner(
const std::vector<geometry_msgs::msg::Point> & points)
{
const auto base = getBaseValues(points);

base_s_vec_ = base.at(0);
const auto & base_x_vec = base.at(1);
const auto & base_y_vec = base.at(2);

// calculate spline coefficients
slerp_x_.calcSplineCoefficients(base_s_vec_, base_x_vec);
slerp_y_.calcSplineCoefficients(base_s_vec_, base_y_vec);
}
26 changes: 26 additions & 0 deletions common/interpolation/test/src/test_spline_interpolation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -272,3 +272,29 @@ TEST(spline_interpolation, SplineInterpolationPoints2d)
single_points.push_back(createPoint(1.0, 0.0, 0.0));
EXPECT_THROW(s.calcSplineCoefficients(single_points), std::logic_error);
}

TEST(spline_interpolation, SplineInterpolationPoints2dPolymorphism)
{
using autoware_auto_planning_msgs::msg::TrajectoryPoint;
using tier4_autoware_utils::createPoint;

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));

std::vector<TrajectoryPoint> trajectory_points;
for (const auto & p : points) {
TrajectoryPoint tp;
tp.pose.position = p;
trajectory_points.push_back(tp);
}

SplineInterpolationPoints2d s_point;
s_point.calcSplineCoefficients(points);
s_point.getSplineInterpolatedPoint(0, 0.);

SplineInterpolationPoints2d s_traj_point;
s_traj_point.calcSplineCoefficients(trajectory_points);
s_traj_point.getSplineInterpolatedPoint(0, 0.);
}

0 comments on commit b2f90a0

Please sign in to comment.