-
Notifications
You must be signed in to change notification settings - Fork 6
/
Copy pathkinematic_vehicle_scenario.cpp
266 lines (240 loc) · 12.8 KB
/
kinematic_vehicle_scenario.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
#include <iostream>
#include <vector>
#include <cmath>
#include <random>
#include <Eigen/Eigen>
#include <filesystem>
#include "matplotlibcpp.h"
#include "distribution/normal_distribution.h"
#include "model/kinematic_vehicle_model.h"
#include "filter/kinematic_vehilce_nkf.h"
#include "filter/kinematic_vehicle_ukf.h"
#include "filter/kinematic_vehicle_ekf.h"
#include "scenario/kinematic_vehicle_scenario.h"
using namespace KinematicVehicle;
int main()
{
KinematicVehicleGaussianScenario scenario;
const size_t N = scenario.N;
const double dt = scenario.dt;
// Kinematic Vehicle Nonlinear Kalman Filter
KinematicVehicleNKF kinematic_vehicle_nkf;
// Normal Vehicle Unscented Kalman Filter
KinematicVehicleUKF kinematic_vehicle_ukf;
// Normal Vehicle Extended Kalman Filter
KinematicVehicleEKF kinematic_vehicle_ekf;
StateInfo nkf_state_info;
nkf_state_info.mean = scenario.ini_mean_;
nkf_state_info.covariance = scenario.ini_cov_;
auto ekf_state_info = nkf_state_info;
auto ukf_state_info = nkf_state_info;
// Initial State
auto x_true = nkf_state_info.mean;
// Noise
const auto& system_noise_map = scenario.system_noise_map_;
const auto& observation_noise_map = scenario.observation_noise_map_;
// Random Variable Generator
std::default_random_engine generator;
auto& wv_dist = scenario.wv_dist_;
auto& wyaw_dist = scenario.wyaw_dist_;
auto& mr_dist = scenario.mr_dist_;
auto& mvc_dist = scenario.mvc_dist_;
auto& myaw_dist = scenario.myaw_dist_;
KinematicVehicleModel vehicle_model;
std::vector<double> times(N);
std::vector<double> nkf_xy_errors(N);
std::vector<double> ekf_xy_errors(N);
std::vector<double> ukf_xy_errors(N);
std::vector<double> nkf_yaw_errors(N);
std::vector<double> ekf_yaw_errors(N);
std::vector<double> ukf_yaw_errors(N);
std::vector<double> nkf_v_errors(N);
std::vector<double> ekf_v_errors(N);
std::vector<double> ukf_v_errors(N);
std::vector<double> x_true_vec(N);
std::vector<double> y_true_vec(N);
std::vector<double> v_true_vec(N);
std::vector<double> yaw_true_vec(N);
std::vector<double> nkf_x_estimate(N);
std::vector<double> nkf_y_estimate(N);
std::vector<double> nkf_v_estimate(N);
std::vector<double> nkf_yaw_estimate(N);
std::vector<double> ekf_x_estimate(N);
std::vector<double> ekf_y_estimate(N);
std::vector<double> ekf_v_estimate(N);
std::vector<double> ekf_yaw_estimate(N);
std::vector<double> ukf_x_estimate(N);
std::vector<double> ukf_y_estimate(N);
std::vector<double> ukf_v_estimate(N);
std::vector<double> ukf_yaw_estimate(N);
for(size_t i=0; i < N; ++i) {
std::cout << "iteration: " << i << std::endl;
Eigen::Vector2d controls(scenario.a_input_(i)*dt, scenario.u_input_(i)*dt);
// Simulate
Eigen::Vector2d system_noise{wv_dist(generator), wyaw_dist(generator)};
Eigen::Vector3d observation_noise{std::max(0.0, mr_dist(generator)), mvc_dist(generator), myaw_dist(generator)};
x_true = vehicle_model.propagate(x_true, controls, system_noise, dt);
auto y_nkf = vehicle_model.observe(x_true, observation_noise);
auto y_ekf = y_nkf;
auto y_ukf = y_nkf;
// Predict
const auto nkf_predicted_info = kinematic_vehicle_nkf.predict(nkf_state_info, controls, dt, system_noise_map);
const auto ekf_predicted_info = kinematic_vehicle_ekf.predict(ekf_state_info, controls, dt, system_noise_map);
const auto ukf_predicted_info = kinematic_vehicle_ukf.predict(ukf_state_info, controls, dt, system_noise_map, observation_noise_map);
const double nkf_yaw_error = normalizeRadian(y_nkf(OBSERVATION::IDX::YAW) - nkf_predicted_info.mean(STATE::IDX::YAW));
const double ekf_yaw_error = normalizeRadian(y_ekf(OBSERVATION::IDX::YAW) - ekf_predicted_info.mean(STATE::IDX::YAW));
const double ukf_yaw_error = normalizeRadian(y_ukf(OBSERVATION::IDX::YAW) - ukf_predicted_info.mean(STATE::IDX::YAW));
y_nkf(OBSERVATION::IDX::YAW) = nkf_yaw_error + nkf_predicted_info.mean(STATE::IDX::YAW);
y_ekf(OBSERVATION::IDX::YAW) = ekf_yaw_error + ekf_predicted_info.mean(STATE::IDX::YAW);
y_ukf(OBSERVATION::IDX::YAW) = ukf_yaw_error + ukf_predicted_info.mean(STATE::IDX::YAW);
// Update
const auto nkf_updated_info = kinematic_vehicle_nkf.update(nkf_predicted_info, y_nkf, observation_noise_map);
const auto ekf_updated_info = kinematic_vehicle_ekf.update(ekf_predicted_info, y_ekf, observation_noise_map);
const auto ukf_updated_info = kinematic_vehicle_ukf.update(ukf_predicted_info, y_ukf, system_noise_map, observation_noise_map);
nkf_state_info = nkf_updated_info;
ekf_state_info = ekf_updated_info;
ukf_state_info = ukf_updated_info;
std::cout << "x_true" << std::endl;
std::cout << x_true << std::endl;
std::cout << "nkf predicted mean" << std::endl;
std::cout << nkf_predicted_info.mean << std::endl;
std::cout << "ekf predicted mean" << std::endl;
std::cout << ekf_predicted_info.mean << std::endl;
std::cout << "ukf predicted mean" << std::endl;
std::cout << ukf_predicted_info.mean << std::endl;
std::cout << "nkf updated mean" << std::endl;
std::cout << nkf_updated_info.mean << std::endl;
std::cout << "ekf updated mean" << std::endl;
std::cout << ekf_updated_info.mean << std::endl;
std::cout << "ukf updated mean" << std::endl;
std::cout << ukf_updated_info.mean << std::endl;
std::cout << "observation" << std::endl;
std::cout << y_ekf << std::endl;
std::cout << "---------------" << std::endl;
{
const double dx = x_true(STATE::IDX::X) - nkf_updated_info.mean(STATE::IDX::X);
const double dy = x_true(STATE::IDX::Y) - nkf_updated_info.mean(STATE::IDX::Y);
const double xy_error = std::sqrt(dx*dx + dy*dy);
const double dv = x_true(STATE::IDX::V) - nkf_updated_info.mean(STATE::IDX::V);
const double nkf_yaw_error = std::abs(x_true(STATE::IDX::YAW) - nkf_updated_info.mean(STATE::IDX::YAW));
std::cout << "nkf_xy_error: " << xy_error << std::endl;
std::cout << "nkf_yaw_error: " << nkf_yaw_error << std::endl;
std::cout << "nkf dv: " << dv << std::endl;
nkf_xy_errors.at(i) = xy_error;
nkf_yaw_errors.at(i) = std::fabs(nkf_yaw_error);
nkf_v_errors.at(i) = std::fabs(dv);
nkf_x_estimate.at(i) = nkf_updated_info.mean(STATE::IDX::X);
nkf_y_estimate.at(i) = nkf_updated_info.mean(STATE::IDX::Y);
nkf_v_estimate.at(i) = nkf_updated_info.mean(STATE::IDX::V);
nkf_yaw_estimate.at(i) = nkf_updated_info.mean(STATE::IDX::YAW);
}
// EKF
{
const double dx = x_true(STATE::IDX::X) - ekf_updated_info.mean(STATE::IDX::X);
const double dy = x_true(STATE::IDX::Y) - ekf_updated_info.mean(STATE::IDX::Y);
const double xy_error = std::sqrt(dx*dx + dy*dy);
const double dv = x_true(STATE::IDX::V) - ekf_updated_info.mean(STATE::IDX::V);
const double ekf_yaw_error = std::abs(x_true(STATE::IDX::YAW) - ekf_updated_info.mean(STATE::IDX::YAW));
std::cout << "ekf_xy_error: " << xy_error << std::endl;
std::cout << "ekf_yaw_error: " << ekf_yaw_error << std::endl;
std::cout << "nkf dv: " << dv << std::endl;
ekf_xy_errors.at(i) = xy_error;
ekf_yaw_errors.at(i) = std::fabs(ekf_yaw_error);
ekf_v_errors.at(i) = std::fabs(dv);
ekf_x_estimate.at(i) = ekf_updated_info.mean(STATE::IDX::X);
ekf_y_estimate.at(i) = ekf_updated_info.mean(STATE::IDX::Y);
ekf_v_estimate.at(i) = ekf_updated_info.mean(STATE::IDX::V);
ekf_yaw_estimate.at(i) = ekf_updated_info.mean(STATE::IDX::YAW);
}
// UKF
{
const double dx = x_true(STATE::IDX::X) - ukf_updated_info.mean(STATE::IDX::X);
const double dy = x_true(STATE::IDX::Y) - ukf_updated_info.mean(STATE::IDX::Y);
const double xy_error = std::sqrt(dx*dx + dy*dy);
const double dv = x_true(STATE::IDX::V) - ukf_updated_info.mean(STATE::IDX::V);
const double ukf_yaw_error = std::abs(x_true(STATE::IDX::YAW) - ukf_updated_info.mean(STATE::IDX::YAW));
std::cout << "ukf_xy_error: " << xy_error << std::endl;
std::cout << "ukf_yaw_error: " << ukf_yaw_error << std::endl;
std::cout << "nkf dv: " << dv << std::endl;
ukf_xy_errors.at(i) = xy_error;
ukf_yaw_errors.at(i) = std::fabs(ukf_yaw_error);
ukf_v_errors.at(i) = std::fabs(dv);
ukf_x_estimate.at(i) = ukf_updated_info.mean(STATE::IDX::X);
ukf_y_estimate.at(i) = ukf_updated_info.mean(STATE::IDX::Y);
ukf_v_estimate.at(i) = ukf_updated_info.mean(STATE::IDX::V);
ukf_yaw_estimate.at(i) = ukf_updated_info.mean(STATE::IDX::YAW);
}
times.at(i) = i*dt;
x_true_vec.at(i) = x_true(STATE::IDX::X);
y_true_vec.at(i) = x_true(STATE::IDX::Y);
v_true_vec.at(i) = x_true(STATE::IDX::V);
yaw_true_vec.at(i) = x_true(STATE::IDX::YAW);
}
// Output data to file
{
std::string parent_dir = "/home/yutaka/CLionProjects/uncertainty_propagation/result";
for(const auto& p : std::filesystem::directory_iterator("../result/"))
{
const auto abs_p = std::filesystem::canonical(p);
const auto flag_find = abs_p.string().find("data");
if(flag_find != std::string::npos) {
parent_dir = abs_p.string();
}
}
const std::string filename = parent_dir + scenario.filename_;
outputResultToFile(filename, times,
x_true_vec, y_true_vec, v_true_vec, yaw_true_vec,
nkf_x_estimate, nkf_y_estimate, nkf_v_estimate, nkf_yaw_estimate,
ekf_x_estimate, ekf_y_estimate, ekf_v_estimate, ekf_yaw_estimate,
ukf_x_estimate, ukf_y_estimate, ukf_v_estimate, ukf_yaw_estimate,
nkf_xy_errors, nkf_v_errors, nkf_yaw_errors,
ekf_xy_errors, ekf_v_errors, ekf_yaw_errors,
ukf_xy_errors, ukf_v_errors, ukf_yaw_errors);
}
double nkf_xy_error_sum = 0.0;
double ekf_xy_error_sum = 0.0;
double ukf_xy_error_sum = 0.0;
double nkf_yaw_error_sum = 0.0;
double ekf_yaw_error_sum = 0.0;
double ukf_yaw_error_sum = 0.0;
double nkf_v_error_sum = 0.0;
double ekf_v_error_sum = 0.0;
double ukf_v_error_sum = 0.0;
for(size_t i=0; i<ukf_xy_errors.size(); ++i) {
nkf_xy_error_sum += nkf_xy_errors.at(i);
ekf_xy_error_sum += ekf_xy_errors.at(i);
ukf_xy_error_sum += ukf_xy_errors.at(i);
nkf_yaw_error_sum += nkf_yaw_errors.at(i);
ekf_yaw_error_sum += ekf_yaw_errors.at(i);
ukf_yaw_error_sum += ukf_yaw_errors.at(i);
nkf_v_error_sum += nkf_v_errors.at(i);
ekf_v_error_sum += ekf_v_errors.at(i);
ukf_v_error_sum += ukf_v_errors.at(i);
}
std::cout << "nkf_xy_error mean: " << nkf_xy_error_sum / N << std::endl;
std::cout << "ekf_xy_error mean: " << ekf_xy_error_sum / N << std::endl;
std::cout << "ukf_xy_error mean: " << ukf_xy_error_sum / N << std::endl;
std::cout << "nkf_yaw_error mean: " << nkf_yaw_error_sum / N << std::endl;
std::cout << "ekf_yaw_error mean: " << ekf_yaw_error_sum / N << std::endl;
std::cout << "ukf_yaw_error mean: " << ukf_yaw_error_sum / N << std::endl;
std::cout << "nkf_v_error mean: " << nkf_v_error_sum / N << std::endl;
std::cout << "ekf_v_error mean: " << ekf_v_error_sum / N << std::endl;
std::cout << "ukf_v_error mean: " << ukf_v_error_sum / N << std::endl;
matplotlibcpp::figure_size(1500, 900);
std::map<std::string, std::string> nkf_keywords;
std::map<std::string, std::string> ekf_keywords;
std::map<std::string, std::string> ukf_keywords;
nkf_keywords.insert(std::pair<std::string, std::string>("label", "nkf error"));
ekf_keywords.insert(std::pair<std::string, std::string>("label", "ekf error"));
ukf_keywords.insert(std::pair<std::string, std::string>("label", "ukf error"));
//matplotlibcpp::plot(times, nkf_xy_errors, nkf_keywords);
//matplotlibcpp::plot(times, ukf_xy_errors, ukf_keywords);
matplotlibcpp::plot(nkf_x_estimate, nkf_y_estimate, nkf_keywords);
matplotlibcpp::plot(ekf_x_estimate, ekf_y_estimate, ekf_keywords);
matplotlibcpp::plot(ukf_x_estimate, ukf_y_estimate, ukf_keywords);
matplotlibcpp::named_plot("true", x_true_vec, y_true_vec);
matplotlibcpp::legend();
matplotlibcpp::title("Result");
matplotlibcpp::show();
return 0;
}