Skip to content

Commit

Permalink
move SplineInterpolationPoints2d to another file
Browse files Browse the repository at this point in the history
Signed-off-by: Takayuki Murooka <takayuki5168@gmail.com>
  • Loading branch information
takayuki5168 committed Feb 15, 2022
1 parent d965378 commit a683cc0
Show file tree
Hide file tree
Showing 6 changed files with 289 additions and 287 deletions.
1 change: 1 addition & 0 deletions common/interpolation/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ ament_auto_find_build_dependencies()
ament_auto_add_library(interpolation SHARED
src/linear_interpolation.cpp
src/spline_interpolation.cpp
src/spline_interpolation_points_2d.cpp
)

# Test
Expand Down
68 changes: 10 additions & 58 deletions common/interpolation/include/interpolation/spline_interpolation.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,82 +49,34 @@ struct MultiSplineCoef
std::vector<double> slerp(
const std::vector<double> & base_keys, const std::vector<double> & base_values,
const std::vector<double> & query_keys);

// std::vector<double> slerpDiff(
// const std::vector<double> & base_keys, const std::vector<double> & base_values,
// const std::vector<double> & query_keys);

// TODO(murooka) use template
// template <typename T>
// std::vector<double> slerpYawFromPoints(const std::vector<T> & points);
std::vector<double> slerpYawFromPoints(const std::vector<geometry_msgs::msg::Point> & points);
} // namespace interpolation

// non-static 1-dimensional spline interpolation
//
// Usage:
// ```
// SplineInterpolation1d spline;
// spline.calcSplineCoefficients(base_keys, base_values); // memorize pre-interpolation result
// internally
// const auto interpolation_result1 = spline.getSplineInterpolatedValues(base_keys,
// query_keys1);
// const auto interpolation_result2 = spline.getSplineInterpolatedValues(base_keys,
// query_keys2);
// SplineInterpolation spline;
// // memorize pre-interpolation result internally
// spline.calcSplineCoefficients(base_keys, base_values);
// const auto interpolation_result1 = spline.getSplineInterpolatedValues(
// base_keys, query_keys1);
// const auto interpolation_result2 = spline.getSplineInterpolatedValues(
// base_keys, query_keys2);
// ```
class SplineInterpolation1d
class SplineInterpolation
{
public:
SplineInterpolation1d() = default;
SplineInterpolation() = default;

void calcSplineCoefficients(
const std::vector<double> & base_keys, const std::vector<double> & base_values);

std::vector<double> getSplineInterpolatedValues(const std::vector<double> & query_keys) const;
std::vector<double> getSplineInterpolatedDiffValues(const std::vector<double> & query_keys) const;

private:
std::vector<double> base_keys_;
interpolation::MultiSplineCoef multi_spline_coef_;
};

// non-static points spline interpolation
// NOTE: We can calculate yaw from the x and y by interpolation derivatives.
//
// Usage:
// ```
// SplineInterpolationPoint2d spline;
// spline.calcSplineCoefficients(base_keys, base_values); // memorize pre-interpolation result
// internally
// const auto interpolation_result1 = spline.getSplineInterpolatedPoints(base_keys,
// query_keys1);
// const auto interpolation_result2 = spline.getSplineInterpolatedPoints(base_keys,
// query_keys2);
// const auto yaw_interpolation_result = spline.getSplineInterpolatedYaws(base_keys,
// query_keys1);
// ```
class SplineInterpolationPoint2d
{
public:
SplineInterpolationPoint2d() = default;

// TODO(murooka) use template
// template <typename T>
// void calcSplineCoefficients(const std::vector<T> & points);
void calcSplineCoefficients(const std::vector<geometry_msgs::msg::Point> & points);

// TODO(murooka) implement these functions
// std::vector<geometry_msgs::msg::Point> getSplineInterpolatedPoints(const double width);
// std::vector<geometry_msgs::msg::Pose> getSplineInterpolatedPoses(const double width);

geometry_msgs::msg::Point getSplineInterpolatedPoint(const size_t idx, const double s) const;
double getSplineInterpolatedYaw(const size_t idx, const double s) const;

double getAccumulatedLength(const size_t idx) const;

private:
interpolation::MultiSplineCoef multi_spline_coef_x_;
interpolation::MultiSplineCoef multi_spline_coef_y_;
std::vector<double> base_s_vec_;
};

#endif // INTERPOLATION__SPLINE_INTERPOLATION_HPP_
Original file line number Diff line number Diff line change
@@ -0,0 +1,71 @@
// Copyright 2021 Tier IV, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef INTERPOLATION__SPLINE_INTERPOLATION_POINTS_2D_HPP_
#define INTERPOLATION__SPLINE_INTERPOLATION_POINTS_2D_HPP_

#include "interpolation/spline_interpolation.hpp"

#include <vector>

namespace interpolation
{
// TODO(murooka) use template
// template <typename T>
// std::vector<double> slerpYawFromPoints(const std::vector<T> & points);
std::vector<double> slerpYawFromPoints(const std::vector<geometry_msgs::msg::Point> & points);
} // namespace interpolation

// non-static points spline interpolation
// NOTE: We can calculate yaw from the x and y by interpolation derivatives.
//
// Usage:
// ```
// SplineInterpolationPoints2d spline;
// // memorize pre-interpolation result internally
// spline.calcSplineCoefficients(base_keys, base_values);
// const auto interpolation_result1 = spline.getSplineInterpolatedPoints(
// base_keys, query_keys1);
// const auto interpolation_result2 = spline.getSplineInterpolatedPoints(
// base_keys, query_keys2);
// const auto yaw_interpolation_result = spline.getSplineInterpolatedYaws(
// base_keys, query_keys1);
// ```
class SplineInterpolationPoints2d
{
public:
SplineInterpolationPoints2d() = default;

// TODO(murooka) use template
// template <typename T>
// void calcSplineCoefficients(const std::vector<T> & points);
void calcSplineCoefficients(const std::vector<geometry_msgs::msg::Point> & points);

// TODO(murooka) implement these functions
// std::vector<geometry_msgs::msg::Point> getSplineInterpolatedPoints(const double width);
// std::vector<geometry_msgs::msg::Pose> getSplineInterpolatedPoses(const double width);

geometry_msgs::msg::Point getSplineInterpolatedPoint(const size_t idx, const double s) const;
double getSplineInterpolatedYaw(const size_t idx, const double s) const;

double getAccumulatedLength(const size_t idx) const;

private:
SplineInterpolation slerp_x_;
SplineInterpolation slerp_y_;

std::vector<double> base_s_vec_;
};

#endif // INTERPOLATION__SPLINE_INTERPOLATION_POINTS_2D_HPP_
Loading

0 comments on commit a683cc0

Please sign in to comment.