Apollo 10.0
自动驾驶开放平台
cruise_mlp_evaluator.cc
浏览该文件的文档.
1/******************************************************************************
2 * Copyright 2018 The Apollo Authors. All Rights Reserved.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *****************************************************************************/
17
18#include <limits>
19#include <utility>
20
21#include <omp.h>
22
23#include "cyber/common/file.h"
32
33namespace apollo {
34namespace prediction {
35
36// Helper function for computing the mean value of a vector.
37double ComputeMean(const std::vector<double>& nums, size_t start, size_t end) {
38 int count = 0;
39 double sum = 0.0;
40 for (size_t i = start; i <= end && i < nums.size(); i++) {
41 sum += nums[i];
42 ++count;
43 }
44 return (count == 0) ? 0.0 : sum / count;
45}
46
51
53
55 ObstaclesContainer* obstacles_container) {
56 // Sanity checks.
57 omp_set_num_threads(1);
58 Clear();
59 CHECK_NOTNULL(obstacle_ptr);
60
61 obstacle_ptr->SetEvaluatorType(evaluator_type_);
62
63 int id = obstacle_ptr->id();
64 if (!obstacle_ptr->latest_feature().IsInitialized()) {
65 AERROR << "Obstacle [" << id << "] has no latest feature.";
66 return false;
67 }
68 Feature* latest_feature_ptr = obstacle_ptr->mutable_latest_feature();
69 CHECK_NOTNULL(latest_feature_ptr);
70 if (!latest_feature_ptr->has_lane() ||
71 !latest_feature_ptr->lane().has_lane_graph()) {
72 ADEBUG << "Obstacle [" << id << "] has no lane graph.";
73 return false;
74 }
75 LaneGraph* lane_graph_ptr =
76 latest_feature_ptr->mutable_lane()->mutable_lane_graph();
77 CHECK_NOTNULL(lane_graph_ptr);
78 if (lane_graph_ptr->lane_sequence().empty()) {
79 AERROR << "Obstacle [" << id << "] has no lane sequences.";
80 return false;
81 }
82
83 ADEBUG << "There are " << lane_graph_ptr->lane_sequence_size()
84 << " lane sequences with probabilities:";
85 // For every possible lane sequence, extract features that are needed
86 // to feed into our trained model.
87 // Then compute the likelihood of the obstacle moving onto that laneseq.
88 for (int i = 0; i < lane_graph_ptr->lane_sequence_size(); ++i) {
89 LaneSequence* lane_sequence_ptr = lane_graph_ptr->mutable_lane_sequence(i);
90 CHECK_NOTNULL(lane_sequence_ptr);
91 std::vector<double> feature_values;
92 ExtractFeatureValues(obstacle_ptr, lane_sequence_ptr, &feature_values);
93 if (feature_values.size() !=
94 OBSTACLE_FEATURE_SIZE + SINGLE_LANE_FEATURE_SIZE * LANE_POINTS_SIZE) {
95 lane_sequence_ptr->set_probability(0.0);
96 ADEBUG << "Skip lane sequence due to incorrect feature size";
97 continue;
98 }
99
100 // Insert features to DataForLearning
101 if (FLAGS_prediction_offline_mode ==
103 std::vector<double> interaction_feature_values;
104 SetInteractionFeatureValues(obstacle_ptr, obstacles_container,
105 lane_sequence_ptr,
106 &interaction_feature_values);
107 if (interaction_feature_values.size() != INTERACTION_FEATURE_SIZE) {
108 ADEBUG << "Obstacle [" << id << "] has fewer than "
109 << "expected lane feature_values"
110 << interaction_feature_values.size() << ".";
111 return false;
112 }
113 ADEBUG << "Interaction feature size = "
114 << interaction_feature_values.size();
115 feature_values.insert(feature_values.end(),
116 interaction_feature_values.begin(),
117 interaction_feature_values.end());
118 FeatureOutput::InsertDataForLearning(*latest_feature_ptr, feature_values,
119 "lane_scanning", lane_sequence_ptr);
120 ADEBUG << "Save extracted features for learning locally.";
121 return true; // Skip Compute probability for offline mode
122 }
123
124 std::vector<torch::jit::IValue> torch_inputs;
125 int input_dim = static_cast<int>(
126 OBSTACLE_FEATURE_SIZE + SINGLE_LANE_FEATURE_SIZE * LANE_POINTS_SIZE);
127 torch::Tensor torch_input = torch::zeros({1, input_dim});
128 for (size_t i = 0; i < feature_values.size(); ++i) {
129 torch_input[0][i] = static_cast<float>(feature_values[i]);
130 }
131 torch_inputs.push_back(std::move(torch_input.to(device_)));
132 if (lane_sequence_ptr->vehicle_on_lane()) {
133 ModelInference(torch_inputs, torch_go_model_, lane_sequence_ptr);
134 } else {
135 ModelInference(torch_inputs, torch_cutin_model_, lane_sequence_ptr);
136 }
137 }
138 return true;
139}
140
142 Obstacle* obstacle_ptr, LaneSequence* lane_sequence_ptr,
143 std::vector<double>* feature_values) {
144 // Sanity checks.
145 CHECK_NOTNULL(obstacle_ptr);
146 CHECK_NOTNULL(lane_sequence_ptr);
147 int id = obstacle_ptr->id();
148
149 // Extract obstacle related features.
150 std::vector<double> obstacle_feature_values;
151 SetObstacleFeatureValues(obstacle_ptr, &obstacle_feature_values);
152 if (obstacle_feature_values.size() != OBSTACLE_FEATURE_SIZE) {
153 ADEBUG << "Obstacle [" << id << "] has fewer than "
154 << "expected obstacle feature_values "
155 << obstacle_feature_values.size() << ".";
156 return;
157 }
158 ADEBUG << "Obstacle feature size = " << obstacle_feature_values.size();
159 feature_values->insert(feature_values->end(), obstacle_feature_values.begin(),
160 obstacle_feature_values.end());
161
162 // Extract lane related features.
163 std::vector<double> lane_feature_values;
164 SetLaneFeatureValues(obstacle_ptr, lane_sequence_ptr, &lane_feature_values);
165 if (lane_feature_values.size() !=
166 SINGLE_LANE_FEATURE_SIZE * LANE_POINTS_SIZE) {
167 ADEBUG << "Obstacle [" << id << "] has fewer than "
168 << "expected lane feature_values" << lane_feature_values.size()
169 << ".";
170 return;
171 }
172 ADEBUG << "Lane feature size = " << lane_feature_values.size();
173 feature_values->insert(feature_values->end(), lane_feature_values.begin(),
174 lane_feature_values.end());
175}
176
177void CruiseMLPEvaluator::SetObstacleFeatureValues(
178 const Obstacle* obstacle_ptr, std::vector<double>* feature_values) {
179 // Sanity checks and variable declarations.
180 CHECK_NOTNULL(obstacle_ptr);
181 feature_values->clear();
182 feature_values->reserve(OBSTACLE_FEATURE_SIZE);
183 std::vector<double> thetas;
184 std::vector<double> lane_ls;
185 std::vector<double> dist_lbs;
186 std::vector<double> dist_rbs;
187 std::vector<int> lane_types;
188 std::vector<double> speeds;
189 std::vector<double> timestamps;
190
191 std::vector<double> has_history(FLAGS_cruise_historical_frame_length, 1.0);
192 std::vector<std::pair<double, double>> pos_history(
193 FLAGS_cruise_historical_frame_length, std::make_pair(0.0, 0.0));
194 std::vector<std::pair<double, double>> vel_history(
195 FLAGS_cruise_historical_frame_length, std::make_pair(0.0, 0.0));
196 std::vector<std::pair<double, double>> acc_history(
197 FLAGS_cruise_historical_frame_length, std::make_pair(0.0, 0.0));
198 std::vector<double> vel_heading_history(FLAGS_cruise_historical_frame_length,
199 0.0);
200 std::vector<double> vel_heading_changing_rate_history(
201 FLAGS_cruise_historical_frame_length, 0.0);
202
203 // Get obstacle's current position to set up the relative coord. system.
204 const Feature& obs_curr_feature = obstacle_ptr->latest_feature();
205 double obs_curr_heading = obs_curr_feature.velocity_heading();
206 std::pair<double, double> obs_curr_pos = std::make_pair(
207 obs_curr_feature.position().x(), obs_curr_feature.position().y());
208 double obs_feature_history_start_time =
209 obstacle_ptr->timestamp() - FLAGS_prediction_trajectory_time_length;
210 int count = 0;
211 // int num_available_history_frames = 0;
212 double prev_timestamp = obs_curr_feature.timestamp();
213
214 // Starting from the most recent timestamp and going backward.
215 ADEBUG << "Obstacle has " << obstacle_ptr->history_size()
216 << " history timestamps.";
217 for (std::size_t i = 0; i < obstacle_ptr->history_size(); ++i) {
218 const Feature& feature = obstacle_ptr->feature(i);
219 if (!feature.IsInitialized()) {
220 continue;
221 }
222 if (feature.timestamp() < obs_feature_history_start_time) {
223 break;
224 }
225 if (!feature.has_lane()) {
226 ADEBUG << "Feature has no lane. Quit.";
227 }
228 // These are for the old 23 features.
229 if (feature.has_lane() && feature.lane().has_lane_feature()) {
230 thetas.push_back(feature.lane().lane_feature().angle_diff());
231 lane_ls.push_back(feature.lane().lane_feature().lane_l());
232 dist_lbs.push_back(feature.lane().lane_feature().dist_to_left_boundary());
233 dist_rbs.push_back(
234 feature.lane().lane_feature().dist_to_right_boundary());
235 lane_types.push_back(feature.lane().lane_feature().lane_turn_type());
236 timestamps.push_back(feature.timestamp());
237 speeds.push_back(feature.speed());
238 ++count;
239 } else {
240 ADEBUG << "Feature has no lane_feature!!!";
241 ADEBUG << feature.lane().current_lane_feature_size();
242 }
243
244 // These are for the new features based on the relative coord. system.
245 if (i >= FLAGS_cruise_historical_frame_length) {
246 continue;
247 }
248 if (i != 0 && has_history[i - 1] == 0.0) {
249 has_history[i] = 0.0;
250 continue;
251 }
252 if (feature.has_position()) {
253 pos_history[i] = WorldCoordToObjCoord(
254 std::make_pair(feature.position().x(), feature.position().y()),
255 obs_curr_pos, obs_curr_heading);
256 } else {
257 has_history[i] = 0.0;
258 }
259 if (feature.has_velocity()) {
260 auto vel_end = WorldCoordToObjCoord(
261 std::make_pair(feature.velocity().x(), feature.velocity().y()),
262 obs_curr_pos, obs_curr_heading);
263 auto vel_begin = WorldCoordToObjCoord(std::make_pair(0.0, 0.0),
264 obs_curr_pos, obs_curr_heading);
265 vel_history[i] = std::make_pair(vel_end.first - vel_begin.first,
266 vel_end.second - vel_begin.second);
267 } else {
268 has_history[i] = 0.0;
269 }
270 if (feature.has_acceleration()) {
271 auto acc_end =
272 WorldCoordToObjCoord(std::make_pair(feature.acceleration().x(),
273 feature.acceleration().y()),
274 obs_curr_pos, obs_curr_heading);
275 auto acc_begin = WorldCoordToObjCoord(std::make_pair(0.0, 0.0),
276 obs_curr_pos, obs_curr_heading);
277 acc_history[i] = std::make_pair(acc_end.first - acc_begin.first,
278 acc_end.second - acc_begin.second);
279 } else {
280 has_history[i] = 0.0;
281 }
282 if (feature.has_velocity_heading()) {
283 vel_heading_history[i] =
284 WorldAngleToObjAngle(feature.velocity_heading(), obs_curr_heading);
285 if (i != 0) {
286 vel_heading_changing_rate_history[i] =
287 (vel_heading_history[i - 1] - vel_heading_history[i]) /
288 (FLAGS_double_precision + feature.timestamp() - prev_timestamp);
289 prev_timestamp = feature.timestamp();
290 }
291 } else {
292 has_history[i] = 0.0;
293 }
294 }
295 if (count <= 0) {
296 ADEBUG << "There is no feature with lane info. Quit.";
297 return;
298 }
299
300 // The following entire part is setting up the old 23 features.
302 int curr_size = 5;
303 int hist_size = static_cast<int>(obstacle_ptr->history_size());
304 double theta_mean = ComputeMean(thetas, 0, hist_size - 1);
305 double theta_filtered = ComputeMean(thetas, 0, curr_size - 1);
306 double lane_l_mean = ComputeMean(lane_ls, 0, hist_size - 1);
307 double lane_l_filtered = ComputeMean(lane_ls, 0, curr_size - 1);
308 double speed_mean = ComputeMean(speeds, 0, hist_size - 1);
309
310 double time_diff = timestamps.front() - timestamps.back();
311 double dist_lb_rate = (timestamps.size() > 1)
312 ? (dist_lbs.front() - dist_lbs.back()) / time_diff
313 : 0.0;
314 double dist_rb_rate = (timestamps.size() > 1)
315 ? (dist_rbs.front() - dist_rbs.back()) / time_diff
316 : 0.0;
317
318 double delta_t = 0.0;
319 if (timestamps.size() > 1) {
320 delta_t = (timestamps.front() - timestamps.back()) /
321 static_cast<double>(timestamps.size() - 1);
322 }
323 double angle_curr = ComputeMean(thetas, 0, curr_size - 1);
324 double angle_prev = ComputeMean(thetas, curr_size, 2 * curr_size - 1);
325 double angle_diff =
326 (hist_size >= 2 * curr_size) ? angle_curr - angle_prev : 0.0;
327
328 double lane_l_curr = ComputeMean(lane_ls, 0, curr_size - 1);
329 double lane_l_prev = ComputeMean(lane_ls, curr_size, 2 * curr_size - 1);
330 double lane_l_diff =
331 (hist_size >= 2 * curr_size) ? lane_l_curr - lane_l_prev : 0.0;
332
333 double angle_diff_rate = 0.0;
334 double lane_l_diff_rate = 0.0;
335 if (delta_t > std::numeric_limits<double>::epsilon()) {
336 angle_diff_rate = angle_diff / (delta_t * curr_size);
337 lane_l_diff_rate = lane_l_diff / (delta_t * curr_size);
338 }
339
340 double acc = 0.0;
341 double jerk = 0.0;
342 if (static_cast<int>(speeds.size()) >= 3 * curr_size &&
343 delta_t > std::numeric_limits<double>::epsilon()) {
344 double speed_1st_recent = ComputeMean(speeds, 0, curr_size - 1);
345 double speed_2nd_recent = ComputeMean(speeds, curr_size, 2 * curr_size - 1);
346 double speed_3rd_recent =
347 ComputeMean(speeds, 2 * curr_size, 3 * curr_size - 1);
348 acc = (speed_1st_recent - speed_2nd_recent) / (curr_size * delta_t);
349 jerk = (speed_1st_recent - 2 * speed_2nd_recent + speed_3rd_recent) /
350 (curr_size * curr_size * delta_t * delta_t);
351 }
352
353 double dist_lb_rate_curr = 0.0;
354 if (hist_size >= 2 * curr_size &&
355 delta_t > std::numeric_limits<double>::epsilon()) {
356 double dist_lb_curr = ComputeMean(dist_lbs, 0, curr_size - 1);
357 double dist_lb_prev = ComputeMean(dist_lbs, curr_size, 2 * curr_size - 1);
358 dist_lb_rate_curr = (dist_lb_curr - dist_lb_prev) / (curr_size * delta_t);
359 }
360
361 double dist_rb_rate_curr = 0.0;
362 if (hist_size >= 2 * curr_size &&
363 delta_t > std::numeric_limits<double>::epsilon()) {
364 double dist_rb_curr = ComputeMean(dist_rbs, 0, curr_size - 1);
365 double dist_rb_prev = ComputeMean(dist_rbs, curr_size, 2 * curr_size - 1);
366 dist_rb_rate_curr = (dist_rb_curr - dist_rb_prev) / (curr_size * delta_t);
367 }
368
369 feature_values->push_back(theta_filtered);
370 feature_values->push_back(theta_mean);
371 feature_values->push_back(theta_filtered - theta_mean);
372 feature_values->push_back(angle_diff);
373 feature_values->push_back(angle_diff_rate);
374
375 feature_values->push_back(lane_l_filtered);
376 feature_values->push_back(lane_l_mean);
377 feature_values->push_back(lane_l_filtered - lane_l_mean);
378 feature_values->push_back(lane_l_diff);
379 feature_values->push_back(lane_l_diff_rate);
380
381 feature_values->push_back(speed_mean);
382 feature_values->push_back(acc);
383 feature_values->push_back(jerk);
384
385 feature_values->push_back(dist_lbs.front());
386 feature_values->push_back(dist_lb_rate);
387 feature_values->push_back(dist_lb_rate_curr);
388
389 feature_values->push_back(dist_rbs.front());
390 feature_values->push_back(dist_rb_rate);
391 feature_values->push_back(dist_rb_rate_curr);
392
393 feature_values->push_back(lane_types.front() == 0 ? 1.0 : 0.0);
394 feature_values->push_back(lane_types.front() == 1 ? 1.0 : 0.0);
395 feature_values->push_back(lane_types.front() == 2 ? 1.0 : 0.0);
396 feature_values->push_back(lane_types.front() == 3 ? 1.0 : 0.0);
397
398 for (std::size_t i = 0; i < FLAGS_cruise_historical_frame_length; i++) {
399 feature_values->push_back(has_history[i]);
400 feature_values->push_back(pos_history[i].first);
401 feature_values->push_back(pos_history[i].second);
402 feature_values->push_back(vel_history[i].first);
403 feature_values->push_back(vel_history[i].second);
404 feature_values->push_back(acc_history[i].first);
405 feature_values->push_back(acc_history[i].second);
406 feature_values->push_back(vel_heading_history[i]);
407 feature_values->push_back(vel_heading_changing_rate_history[i]);
408 }
409}
410
411void CruiseMLPEvaluator::SetInteractionFeatureValues(
412 Obstacle* obstacle_ptr, ObstaclesContainer* obstacles_container,
413 LaneSequence* lane_sequence_ptr, std::vector<double>* feature_values) {
414 // forward / backward: relative_s, relative_l, speed, length
415 feature_values->clear();
416 // Initialize forward and backward obstacles
417 NearbyObstacle forward_obstacle;
418 NearbyObstacle backward_obstacle;
419 forward_obstacle.set_s(FLAGS_default_s_if_no_obstacle_in_lane_sequence);
420 forward_obstacle.set_l(FLAGS_default_l_if_no_obstacle_in_lane_sequence);
421 backward_obstacle.set_s(-FLAGS_default_s_if_no_obstacle_in_lane_sequence);
422 backward_obstacle.set_l(FLAGS_default_l_if_no_obstacle_in_lane_sequence);
423
424 for (const auto& nearby_obstacle : lane_sequence_ptr->nearby_obstacle()) {
425 if (nearby_obstacle.s() < 0.0) {
426 if (nearby_obstacle.s() > backward_obstacle.s()) {
427 backward_obstacle.set_id(nearby_obstacle.id());
428 backward_obstacle.set_s(nearby_obstacle.s());
429 backward_obstacle.set_l(nearby_obstacle.l());
430 }
431 } else {
432 if (nearby_obstacle.s() < forward_obstacle.s()) {
433 forward_obstacle.set_id(nearby_obstacle.id());
434 forward_obstacle.set_s(nearby_obstacle.s());
435 forward_obstacle.set_l(nearby_obstacle.l());
436 }
437 }
438 }
439
440 // Set feature values for forward obstacle
441 feature_values->push_back(forward_obstacle.s());
442 feature_values->push_back(forward_obstacle.l());
443 if (!forward_obstacle.has_id()) { // no forward obstacle
444 feature_values->push_back(0.0);
445 feature_values->push_back(0.0);
446 } else {
447 Obstacle* forward_obs_ptr =
448 obstacles_container->GetObstacle(forward_obstacle.id());
449 if (forward_obs_ptr) {
450 const Feature& feature = forward_obs_ptr->latest_feature();
451 feature_values->push_back(feature.length());
452 feature_values->push_back(feature.speed());
453 }
454 }
455
456 // Set feature values for backward obstacle
457 feature_values->push_back(backward_obstacle.s());
458 feature_values->push_back(backward_obstacle.l());
459 if (!backward_obstacle.has_id()) { // no forward obstacle
460 feature_values->push_back(0.0);
461 feature_values->push_back(0.0);
462 } else {
463 Obstacle* backward_obs_ptr =
464 obstacles_container->GetObstacle(backward_obstacle.id());
465 if (backward_obs_ptr) {
466 const Feature& feature = backward_obs_ptr->latest_feature();
467 feature_values->push_back(feature.length());
468 feature_values->push_back(feature.speed());
469 }
470 }
471}
472
473void CruiseMLPEvaluator::SetLaneFeatureValues(
474 const Obstacle* obstacle_ptr, const LaneSequence* lane_sequence_ptr,
475 std::vector<double>* feature_values) {
476 // Sanity checks.
477 feature_values->clear();
478 feature_values->reserve(SINGLE_LANE_FEATURE_SIZE * LANE_POINTS_SIZE);
479 const Feature& feature = obstacle_ptr->latest_feature();
480 if (!feature.IsInitialized()) {
481 ADEBUG << "Obstacle [" << obstacle_ptr->id() << "] has no latest feature.";
482 return;
483 } else if (!feature.has_position()) {
484 ADEBUG << "Obstacle [" << obstacle_ptr->id() << "] has no position.";
485 return;
486 }
487
488 double heading = feature.velocity_heading();
489 for (int i = 0; i < lane_sequence_ptr->lane_segment_size(); ++i) {
490 if (feature_values->size() >= SINGLE_LANE_FEATURE_SIZE * LANE_POINTS_SIZE) {
491 break;
492 }
493 const LaneSegment& lane_segment = lane_sequence_ptr->lane_segment(i);
494 for (int j = 0; j < lane_segment.lane_point_size(); ++j) {
495 if (feature_values->size() >=
496 SINGLE_LANE_FEATURE_SIZE * LANE_POINTS_SIZE) {
497 break;
498 }
499 const LanePoint& lane_point = lane_segment.lane_point(j);
500 if (!lane_point.has_position()) {
501 AERROR << "Lane point has no position.";
502 continue;
503 }
504
505 std::pair<double, double> relative_s_l = WorldCoordToObjCoord(
506 std::make_pair(lane_point.position().x(), lane_point.position().y()),
507 std::make_pair(feature.position().x(), feature.position().y()),
508 heading);
509 double relative_ang = WorldAngleToObjAngle(lane_point.heading(), heading);
510
511 feature_values->push_back(relative_s_l.second);
512 feature_values->push_back(relative_s_l.first);
513 feature_values->push_back(relative_ang);
514 feature_values->push_back(lane_point.kappa());
515 }
516 }
517
518 // If the lane points are not sufficient, apply a linear extrapolation.
519 std::size_t size = feature_values->size();
520 while (size >= 10 && size < SINGLE_LANE_FEATURE_SIZE * LANE_POINTS_SIZE) {
521 double relative_l_new = 2 * feature_values->operator[](size - 5) -
522 feature_values->operator[](size - 10);
523 double relative_s_new = 2 * feature_values->operator[](size - 4) -
524 feature_values->operator[](size - 9);
525 double relative_ang_new = feature_values->operator[](size - 3);
526
527 feature_values->push_back(relative_l_new);
528 feature_values->push_back(relative_s_new);
529 feature_values->push_back(relative_ang_new);
530 feature_values->push_back(0.0);
531
532 size = feature_values->size();
533 }
534}
535
536void CruiseMLPEvaluator::LoadModels() {
537 if (FLAGS_use_cuda && torch::cuda::is_available()) {
538 ADEBUG << "CUDA is available";
539 device_ = torch::Device(torch::kCUDA);
540 }
541 torch::set_num_threads(1);
542 torch_go_model_ =
543 torch::jit::load(FLAGS_torch_vehicle_cruise_go_file, device_);
544 torch_cutin_model_ =
545 torch::jit::load(FLAGS_torch_vehicle_cruise_cutin_file, device_);
546 std::vector<torch::jit::IValue> torch_inputs;
547 int input_dim = static_cast<int>(
548 OBSTACLE_FEATURE_SIZE + SINGLE_LANE_FEATURE_SIZE * LANE_POINTS_SIZE);
549 torch::Tensor torch_input = torch::randn({1, input_dim});
550 torch_inputs.push_back(
551 std::move(torch_input.to(device_)));
552 // Warm up to avoid very slow first inference later
553 WarmUp(torch_inputs, &torch_go_model_, nullptr);
554 WarmUp(torch_inputs, &torch_cutin_model_, nullptr);
555}
556
557void CruiseMLPEvaluator::ModelInference(
558 const std::vector<torch::jit::IValue>& torch_inputs,
559 torch::jit::script::Module torch_model_ptr,
560 LaneSequence* lane_sequence_ptr) {
561 auto torch_output_tuple = torch_model_ptr.forward(torch_inputs).toTuple();
562 auto probability_tensor =
563 torch_output_tuple->elements()[0].toTensor().to(torch::kCPU);
564 auto finish_time_tensor =
565 torch_output_tuple->elements()[1].toTensor().to(torch::kCPU);
566 lane_sequence_ptr->set_probability(apollo::common::math::Sigmoid(
567 static_cast<double>(probability_tensor.accessor<float, 2>()[0][0])));
568 lane_sequence_ptr->set_time_to_lane_center(
569 static_cast<double>(finish_time_tensor.accessor<float, 2>()[0][0]));
570}
571
572} // namespace prediction
573} // namespace apollo
void ExtractFeatureValues(Obstacle *obstacle_ptr, LaneSequence *lane_sequence_ptr, std::vector< double > *feature_values)
Extract feature vector
bool Evaluate(Obstacle *obstacle_ptr, ObstaclesContainer *obstacles_container) override
Override Evaluate
double WorldAngleToObjAngle(double input_world_angle, double obj_world_angle)
Definition evaluator.h:116
std::pair< double, double > WorldCoordToObjCoord(std::pair< double, double > input_world_coord, std::pair< double, double > obj_world_coord, double obj_world_angle)
Definition evaluator.h:94
ObstacleConf::EvaluatorType evaluator_type_
Definition evaluator.h:156
static void InsertDataForLearning(const Feature &feature, const std::vector< double > &feature_values, const std::string &category, const LaneSequence *lane_sequence_ptr)
Insert a data_for_learning
Prediction obstacle.
Definition obstacle.h:52
double timestamp() const
Get the obstacle's timestamp.
Definition obstacle.cc:62
Feature * mutable_latest_feature()
Get a pointer to the latest feature.
Definition obstacle.cc:88
int id() const
Get the obstacle's ID.
Definition obstacle.cc:60
size_t history_size() const
Get the number of historical features.
Definition obstacle.cc:93
const Feature & feature(const size_t i) const
Get the ith feature from latest to earliest.
Definition obstacle.cc:67
void SetEvaluatorType(const ObstacleConf::EvaluatorType &evaluator_type)
Definition obstacle.cc:1484
const Feature & latest_feature() const
Get the latest feature.
Definition obstacle.cc:78
Use container manager to manage all containers
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44
double Sigmoid(const double x)
Definition math_utils.h:171
void WarmUp(const std::vector< torch::jit::IValue > &torch_inputs, torch::jit::script::Module *model, at::Tensor *default_output_ptr)
warm up function to avoid slowly inference of torch model
Definition warm_up.cc:28
double ComputeMean(const std::vector< double > &nums, size_t start, size_t end)
class register implement
Definition arena_queue.h:37
Obstacles container
Holds all global constants for the prediction module.
optional apollo::common::Point3D velocity
Definition feature.proto:90
optional double velocity_heading
Definition feature.proto:93
optional apollo::common::Point3D position
Definition feature.proto:88
optional apollo::common::Point3D acceleration
Definition feature.proto:92
repeated LaneSequence lane_sequence
warm-up function for torch model to avoid first multiple slowly inference