12
12
// See the License for the specific language governing permissions and
13
13
// limitations under the License.
14
14
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"
15
18
#include " autoware/motion_utils/trajectory_container/interpolator/linear.hpp"
19
+ #include " autoware/motion_utils/trajectory_container/interpolator/nearest_neighbor.hpp"
16
20
17
21
#include < autoware/motion_utils/trajectory_container/interpolator.hpp>
18
22
@@ -27,26 +31,25 @@ int main()
27
31
auto plt = matplotlibcpp17::pyplot::import ();
28
32
29
33
// 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 };
31
35
std::vector<double > values;
32
36
std::random_device seed_gen;
33
37
std::mt19937 engine (seed_gen ());
34
38
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) {
36
40
values.push_back (dist (engine));
37
41
}
38
42
// Scatter Data
39
- plt.scatter (Args (axis , values));
43
+ plt.scatter (Args (bases , values));
40
44
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;
43
46
// Linear Interpolator
44
47
{
45
48
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 ();
47
50
std::vector<double > x;
48
51
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 ) {
50
53
x.push_back (i);
51
54
y.push_back (interpolator.compute (i));
52
55
}
@@ -56,11 +59,11 @@ int main()
56
59
// AkimaSpline Interpolator
57
60
{
58
61
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 ();
61
64
std::vector<double > x;
62
65
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 ) {
64
67
x.push_back (i);
65
68
y.push_back (interpolator.compute (i));
66
69
}
@@ -70,11 +73,10 @@ int main()
70
73
// CubicSpline Interpolator
71
74
{
72
75
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 ();
75
77
std::vector<double > x;
76
78
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 ) {
78
80
x.push_back (i);
79
81
y.push_back (interpolator.compute (i));
80
82
}
@@ -85,10 +87,10 @@ int main()
85
87
{
86
88
using autoware::motion_utils::trajectory_container::interpolator::NearestNeighbor;
87
89
auto interpolator =
88
- *InterpolatorCreator< NearestNeighbor<double >>(). set_axis (axis ).set_values (values).create ();
90
+ *NearestNeighbor<double >::Builder{}. set_bases (bases ).set_values (values).build ();
89
91
std::vector<double > x;
90
92
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 ) {
92
94
x.push_back (i);
93
95
y.push_back (interpolator.compute (i));
94
96
}
@@ -98,11 +100,10 @@ int main()
98
100
// Stairstep Interpolator
99
101
{
100
102
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 ();
103
104
std::vector<double > x;
104
105
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 ) {
106
107
x.push_back (i);
107
108
y.push_back (interpolator.compute (i));
108
109
}
0 commit comments