Skip to content

Commit f77acfe

Browse files
authored
refactor(autoware_motion_utils): refactor interpolator (#8931)
* refactor interpolator Signed-off-by: Y.Hisaki <yhisaki31@gmail.com> * update cmake Signed-off-by: Y.Hisaki <yhisaki31@gmail.com> * update Signed-off-by: Y.Hisaki <yhisaki31@gmail.com> * rename Signed-off-by: Y.Hisaki <yhisaki31@gmail.com> * Update CMakeLists.txt --------- Signed-off-by: Y.Hisaki <yhisaki31@gmail.com>
1 parent 71cfaaf commit f77acfe

18 files changed

+218
-288
lines changed

common/autoware_motion_utils/CMakeLists.txt

+1-5
Original file line numberDiff line numberDiff line change
@@ -7,16 +7,11 @@ find_package(autoware_cmake REQUIRED)
77
autoware_package()
88

99
find_package(Boost REQUIRED)
10-
find_package(fmt REQUIRED)
1110

1211
ament_auto_add_library(autoware_motion_utils SHARED
1312
DIRECTORY src
1413
)
1514

16-
target_link_libraries(autoware_motion_utils
17-
fmt::fmt
18-
)
19-
2015
if(BUILD_TESTING)
2116
find_package(ament_cmake_ros REQUIRED)
2217

@@ -45,6 +40,7 @@ if(BUILD_EXAMPLES)
4540
foreach(example_file ${example_files})
4641
get_filename_component(example_name ${example_file} NAME_WE)
4742
ament_auto_add_executable(${example_name} ${example_file})
43+
set_source_files_properties(${example_file} PROPERTIES COMPILE_FLAGS -Wno-error -Wno-attributes -Wno-unused-parameter)
4844
target_link_libraries(${example_name}
4945
autoware_motion_utils
5046
matplotlibcpp17::matplotlibcpp17

common/autoware_motion_utils/examples/example_interpolator.cpp

+19-18
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,11 @@
1212
// See the License for the specific language governing permissions and
1313
// limitations under the License.
1414

15+
#include "autoware/motion_utils/trajectory_container/interpolator/akima_spline.hpp"
16+
#include "autoware/motion_utils/trajectory_container/interpolator/cubic_spline.hpp"
17+
#include "autoware/motion_utils/trajectory_container/interpolator/interpolator.hpp"
1518
#include "autoware/motion_utils/trajectory_container/interpolator/linear.hpp"
19+
#include "autoware/motion_utils/trajectory_container/interpolator/nearest_neighbor.hpp"
1620

1721
#include <autoware/motion_utils/trajectory_container/interpolator.hpp>
1822

@@ -27,26 +31,25 @@ int main()
2731
auto plt = matplotlibcpp17::pyplot::import();
2832

2933
// create random values
30-
std::vector<double> axis = {0.0, 1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0};
34+
std::vector<double> bases = {0.0, 1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0};
3135
std::vector<double> values;
3236
std::random_device seed_gen;
3337
std::mt19937 engine(seed_gen());
3438
std::uniform_real_distribution<> dist(-1.0, 1.0);
35-
for (size_t i = 0; i < axis.size(); ++i) {
39+
for (size_t i = 0; i < bases.size(); ++i) {
3640
values.push_back(dist(engine));
3741
}
3842
// Scatter Data
39-
plt.scatter(Args(axis, values));
43+
plt.scatter(Args(bases, values));
4044

41-
using autoware::motion_utils::trajectory_container::interpolator::Interpolator;
42-
using autoware::motion_utils::trajectory_container::interpolator::InterpolatorCreator;
45+
using autoware::motion_utils::trajectory_container::interpolator::InterpolatorInterface;
4346
// Linear Interpolator
4447
{
4548
using autoware::motion_utils::trajectory_container::interpolator::Linear;
46-
auto interpolator = *InterpolatorCreator<Linear>().set_axis(axis).set_values(values).create();
49+
auto interpolator = *Linear::Builder{}.set_bases(bases).set_values(values).build();
4750
std::vector<double> x;
4851
std::vector<double> y;
49-
for (double i = axis.front(); i < axis.back(); i += 0.01) {
52+
for (double i = bases.front(); i < bases.back(); i += 0.01) {
5053
x.push_back(i);
5154
y.push_back(interpolator.compute(i));
5255
}
@@ -56,11 +59,11 @@ int main()
5659
// AkimaSpline Interpolator
5760
{
5861
using autoware::motion_utils::trajectory_container::interpolator::AkimaSpline;
59-
auto interpolator =
60-
*InterpolatorCreator<AkimaSpline>().set_axis(axis).set_values(values).create();
62+
63+
auto interpolator = *AkimaSpline::Builder{}.set_bases(bases).set_values(values).build();
6164
std::vector<double> x;
6265
std::vector<double> y;
63-
for (double i = axis.front(); i < axis.back(); i += 0.01) {
66+
for (double i = bases.front(); i < bases.back(); i += 0.01) {
6467
x.push_back(i);
6568
y.push_back(interpolator.compute(i));
6669
}
@@ -70,11 +73,10 @@ int main()
7073
// CubicSpline Interpolator
7174
{
7275
using autoware::motion_utils::trajectory_container::interpolator::CubicSpline;
73-
auto interpolator =
74-
*InterpolatorCreator<CubicSpline>().set_axis(axis).set_values(values).create();
76+
auto interpolator = *CubicSpline::Builder{}.set_bases(bases).set_values(values).build();
7577
std::vector<double> x;
7678
std::vector<double> y;
77-
for (double i = axis.front(); i < axis.back(); i += 0.01) {
79+
for (double i = bases.front(); i < bases.back(); i += 0.01) {
7880
x.push_back(i);
7981
y.push_back(interpolator.compute(i));
8082
}
@@ -85,10 +87,10 @@ int main()
8587
{
8688
using autoware::motion_utils::trajectory_container::interpolator::NearestNeighbor;
8789
auto interpolator =
88-
*InterpolatorCreator<NearestNeighbor<double>>().set_axis(axis).set_values(values).create();
90+
*NearestNeighbor<double>::Builder{}.set_bases(bases).set_values(values).build();
8991
std::vector<double> x;
9092
std::vector<double> y;
91-
for (double i = axis.front(); i < axis.back(); i += 0.01) {
93+
for (double i = bases.front(); i < bases.back(); i += 0.01) {
9294
x.push_back(i);
9395
y.push_back(interpolator.compute(i));
9496
}
@@ -98,11 +100,10 @@ int main()
98100
// Stairstep Interpolator
99101
{
100102
using autoware::motion_utils::trajectory_container::interpolator::Stairstep;
101-
auto interpolator =
102-
*InterpolatorCreator<Stairstep<double>>().set_axis(axis).set_values(values).create();
103+
auto interpolator = *Stairstep<double>::Builder{}.set_bases(bases).set_values(values).build();
103104
std::vector<double> x;
104105
std::vector<double> y;
105-
for (double i = axis.front(); i < axis.back(); i += 0.01) {
106+
for (double i = bases.front(); i < bases.back(); i += 0.01) {
106107
x.push_back(i);
107108
y.push_back(interpolator.compute(i));
108109
}

common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator.hpp

-1
Original file line numberDiff line numberDiff line change
@@ -16,7 +16,6 @@
1616
#define AUTOWARE__MOTION_UTILS__TRAJECTORY_CONTAINER__INTERPOLATOR_HPP_
1717
#include <autoware/motion_utils/trajectory_container/interpolator/akima_spline.hpp>
1818
#include <autoware/motion_utils/trajectory_container/interpolator/cubic_spline.hpp>
19-
#include <autoware/motion_utils/trajectory_container/interpolator/interpolator_creator.hpp>
2019
#include <autoware/motion_utils/trajectory_container/interpolator/linear.hpp>
2120
#include <autoware/motion_utils/trajectory_container/interpolator/nearest_neighbor.hpp>
2221
#include <autoware/motion_utils/trajectory_container/interpolator/stairstep.hpp>

common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/akima_spline.hpp

+6-15
Original file line numberDiff line numberDiff line change
@@ -15,11 +15,10 @@
1515
#ifndef AUTOWARE__MOTION_UTILS__TRAJECTORY_CONTAINER__INTERPOLATOR__AKIMA_SPLINE_HPP_
1616
#define AUTOWARE__MOTION_UTILS__TRAJECTORY_CONTAINER__INTERPOLATOR__AKIMA_SPLINE_HPP_
1717

18-
#include "autoware/motion_utils/trajectory_container/interpolator/interpolator.hpp"
18+
#include "autoware/motion_utils/trajectory_container/interpolator/detail/interpolator_mixin.hpp"
1919

2020
#include <Eigen/Dense>
2121

22-
#include <memory>
2322
#include <vector>
2423

2524
namespace autoware::motion_utils::trajectory_container::interpolator
@@ -30,7 +29,7 @@ namespace autoware::motion_utils::trajectory_container::interpolator
3029
*
3130
* This class provides methods to perform Akima spline interpolation on a set of data points.
3231
*/
33-
class AkimaSpline : public Interpolator<double>
32+
class AkimaSpline : public detail::InterpolatorMixin<AkimaSpline, double>
3433
{
3534
private:
3635
Eigen::VectorXd a_, b_, c_, d_; ///< Coefficients for the Akima spline.
@@ -40,21 +39,20 @@ class AkimaSpline : public Interpolator<double>
4039
*
4140
* This method computes the coefficients for the Akima spline.
4241
*
43-
* @param axis The axis values.
42+
* @param bases The bases values.
4443
* @param values The values to interpolate.
4544
*/
4645
void compute_parameters(
47-
const Eigen::Ref<const Eigen::VectorXd> & axis,
46+
const Eigen::Ref<const Eigen::VectorXd> & bases,
4847
const Eigen::Ref<const Eigen::VectorXd> & values);
4948

5049
/**
5150
* @brief Build the interpolator with the given values.
5251
*
53-
* @param axis The axis values.
52+
* @param bases The bases values.
5453
* @param values The values to interpolate.
5554
*/
56-
void build_impl(
57-
const Eigen::Ref<const Eigen::VectorXd> & axis, const std::vector<double> & values) override;
55+
void build_impl(const std::vector<double> & bases, const std::vector<double> & values) override;
5856

5957
/**
6058
* @brief Compute the interpolated value at the given point.
@@ -89,13 +87,6 @@ class AkimaSpline : public Interpolator<double>
8987
* @return The minimum number of required points.
9088
*/
9189
[[nodiscard]] size_t minimum_required_points() const override { return 5; }
92-
93-
/**
94-
* @brief Clone the interpolator.
95-
*
96-
* @return A shared pointer to a new instance of the interpolator.
97-
*/
98-
[[nodiscard]] std::shared_ptr<Interpolator<double>> clone() const override;
9990
};
10091

10192
} // namespace autoware::motion_utils::trajectory_container::interpolator

common/autoware_motion_utils/include/autoware/motion_utils/trajectory_container/interpolator/cubic_spline.hpp

+7-15
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@
1515
#ifndef AUTOWARE__MOTION_UTILS__TRAJECTORY_CONTAINER__INTERPOLATOR__CUBIC_SPLINE_HPP_
1616
#define AUTOWARE__MOTION_UTILS__TRAJECTORY_CONTAINER__INTERPOLATOR__CUBIC_SPLINE_HPP_
1717

18-
#include "autoware/motion_utils/trajectory_container/interpolator/interpolator.hpp"
18+
#include "autoware/motion_utils/trajectory_container/interpolator/detail/interpolator_mixin.hpp"
1919

2020
#include <Eigen/Dense>
2121

@@ -29,33 +29,32 @@ namespace autoware::motion_utils::trajectory_container::interpolator
2929
*
3030
* This class provides methods to perform cubic spline interpolation on a set of data points.
3131
*/
32-
class CubicSpline : public Interpolator<double>
32+
class CubicSpline : public detail::InterpolatorMixin<CubicSpline, double>
3333
{
3434
private:
3535
Eigen::VectorXd a_, b_, c_, d_; ///< Coefficients for the cubic spline.
36-
Eigen::VectorXd h_; ///< Interval sizes between axis points.
36+
Eigen::VectorXd h_; ///< Interval sizes between bases points.
3737

3838
/**
3939
* @brief Compute the spline parameters.
4040
*
4141
* This method computes the coefficients for the cubic spline.
4242
*
43-
* @param axis The axis values.
43+
* @param bases The bases values.
4444
* @param values The values to interpolate.
4545
*/
4646
void compute_parameters(
47-
const Eigen::Ref<const Eigen::VectorXd> & axis,
47+
const Eigen::Ref<const Eigen::VectorXd> & bases,
4848
const Eigen::Ref<const Eigen::VectorXd> & values);
4949

5050
/**
5151
* @brief Build the interpolator with the given values.
5252
*
53-
* @param axis The axis values.
53+
* @param bases The bases values.
5454
* @param values The values to interpolate.
5555
* @return True if the interpolator was built successfully, false otherwise.
5656
*/
57-
void build_impl(
58-
const Eigen::Ref<const Eigen::VectorXd> & axis, const std::vector<double> & values) override;
57+
void build_impl(const std::vector<double> & bases, const std::vector<double> & values) override;
5958

6059
/**
6160
* @brief Compute the interpolated value at the given point.
@@ -90,13 +89,6 @@ class CubicSpline : public Interpolator<double>
9089
* @return The minimum number of required points.
9190
*/
9291
[[nodiscard]] size_t minimum_required_points() const override { return 4; }
93-
94-
/**
95-
* @brief Clone the interpolator.
96-
*
97-
* @return A shared pointer to a new instance of the interpolator.
98-
*/
99-
[[nodiscard]] std::shared_ptr<Interpolator<double>> clone() const override;
10092
};
10193

10294
} // namespace autoware::motion_utils::trajectory_container::interpolator
+18-20
Original file line numberDiff line numberDiff line change
@@ -13,15 +13,13 @@
1313
// limitations under the License.
1414

1515
// clang-format off
16-
#ifndef AUTOWARE__MOTION_UTILS__TRAJECTORY_CONTAINER__INTERPOLATOR__DETAIL__INTERPOLATOR_COMMON_IMPL_HPP_ // NOLINT
17-
#define AUTOWARE__MOTION_UTILS__TRAJECTORY_CONTAINER__INTERPOLATOR__DETAIL__INTERPOLATOR_COMMON_IMPL_HPP_ // NOLINT
16+
#ifndef AUTOWARE__MOTION_UTILS__TRAJECTORY_CONTAINER__INTERPOLATOR__DETAIL__INTERPOLATOR_COMMON_INTERFACE_HPP_ // NOLINT
17+
#define AUTOWARE__MOTION_UTILS__TRAJECTORY_CONTAINER__INTERPOLATOR__DETAIL__INTERPOLATOR_COMMON_INTERFACE_HPP_ // NOLINT
1818
// clang-format on
1919

2020
#include <Eigen/Dense>
2121
#include <rclcpp/logging.hpp>
2222

23-
#include <fmt/format.h>
24-
2523
#include <vector>
2624

2725
namespace autoware::motion_utils::trajectory_container::interpolator::detail
@@ -35,20 +33,20 @@ namespace autoware::motion_utils::trajectory_container::interpolator::detail
3533
* @tparam T The type of the values being interpolated.
3634
*/
3735
template <typename T>
38-
class InterpolatorCommonImpl
36+
class InterpolatorCommonInterface
3937
{
4038
protected:
41-
Eigen::VectorXd axis_; ///< Axis values for the interpolation.
39+
std::vector<double> bases_; ///< bases values for the interpolation.
4240

4341
/**
4442
* @brief Get the start of the interpolation range.
4543
*/
46-
[[nodiscard]] double start() const { return axis_(0); }
44+
[[nodiscard]] double start() const { return bases_.front(); }
4745

4846
/**
4947
* @brief Get the end of the interpolation range.
5048
*/
51-
[[nodiscard]] double end() const { return axis_(axis_.size() - 1); }
49+
[[nodiscard]] double end() const { return bases_.back(); }
5250

5351
/**
5452
* @brief Compute the interpolated value at the given point.
@@ -65,11 +63,10 @@ class InterpolatorCommonImpl
6563
*
6664
* This method should be overridden by subclasses to provide the specific build logic.
6765
*
68-
* @param axis The axis values.
66+
* @param bases The bases values.
6967
* @param values The values to interpolate.
7068
*/
71-
virtual void build_impl(
72-
const Eigen::Ref<const Eigen::VectorXd> & axis, const std::vector<T> & values) = 0;
69+
virtual void build_impl(const std::vector<double> & bases, const std::vector<T> & values) = 0;
7370

7471
/**
7572
* @brief Validate the input to the compute method.
@@ -91,29 +88,30 @@ class InterpolatorCommonImpl
9188
[[nodiscard]] int32_t get_index(const double & s, bool end_inclusive = true) const
9289
{
9390
if (end_inclusive && s == end()) {
94-
return static_cast<int32_t>(axis_.size()) - 2;
91+
return static_cast<int32_t>(bases_.size()) - 2;
9592
}
9693
auto comp = [](const double & a, const double & b) { return a <= b; };
97-
return std::distance(axis_.begin(), std::lower_bound(axis_.begin(), axis_.end(), s, comp)) - 1;
94+
return std::distance(bases_.begin(), std::lower_bound(bases_.begin(), bases_.end(), s, comp)) -
95+
1;
9896
}
9997

10098
public:
10199
/**
102-
* @brief Build the interpolator with the given axis and values.
100+
* @brief Build the interpolator with the given bases and values.
103101
*
104-
* @param axis The axis values.
102+
* @param bases The bases values.
105103
* @param values The values to interpolate.
106104
* @return True if the interpolator was built successfully, false otherwise.
107105
*/
108-
bool build(const Eigen::Ref<const Eigen::VectorXd> & axis, const std::vector<T> & values)
106+
bool build(const std::vector<double> & bases, const std::vector<T> & values)
109107
{
110-
if (axis.size() != static_cast<Eigen::Index>(values.size())) {
108+
if (bases.size() != values.size()) {
111109
return false;
112110
}
113-
if (axis.size() < static_cast<Eigen::Index>(minimum_required_points())) {
111+
if (bases.size() < minimum_required_points()) {
114112
return false;
115113
}
116-
build_impl(axis, values);
114+
build_impl(bases, values);
117115
return true;
118116
}
119117

@@ -141,5 +139,5 @@ class InterpolatorCommonImpl
141139
} // namespace autoware::motion_utils::trajectory_container::interpolator::detail
142140

143141
// clang-format off
144-
#endif // AUTOWARE__MOTION_UTILS__TRAJECTORY_CONTAINER__INTERPOLATOR__DETAIL__INTERPOLATOR_COMMON_IMPL_HPP_ // NOLINT
142+
#endif // AUTOWARE__MOTION_UTILS__TRAJECTORY_CONTAINER__INTERPOLATOR__DETAIL__INTERPOLATOR_COMMON_INTERFACE_HPP_ // NOLINT
145143
// clang-format on

0 commit comments

Comments
 (0)