obstacle.cc 38.5 KB
Newer Older
K
kechxu 已提交
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18
/******************************************************************************
 * Copyright 2017 The Apollo Authors. All Rights Reserved.
 *
 * 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.
 *****************************************************************************/

#include "modules/prediction/container/obstacles/obstacle.h"

19
#include <algorithm>
20
#include <cmath>
D
Dong Li 已提交
21
#include <iomanip>
22
#include <limits>
K
kechxu 已提交
23
#include <unordered_set>
C
Calvin Miao 已提交
24
#include <utility>
25

D
Dong Li 已提交
26
#include "modules/common/configs/config_gflags.h"
27 28
#include "modules/common/log.h"
#include "modules/common/math/math_utils.h"
29
#include "modules/common/util/map_util.h"
K
kechxu 已提交
30
#include "modules/prediction/common/prediction_gflags.h"
31
#include "modules/prediction/common/prediction_map.h"
32
#include "modules/prediction/common/road_graph.h"
33
#include "modules/prediction/container/obstacles/obstacle_clusters.h"
C
Calvin Miao 已提交
34
#include "modules/prediction/network/rnn_model/rnn_model.h"
35

K
kechxu 已提交
36 37 38
namespace apollo {
namespace prediction {

39 40 41 42 43
using ::apollo::common::ErrorCode;
using ::apollo::common::Point3D;
using ::apollo::common::math::KalmanFilter;
using ::apollo::common::util::FindOrDie;
using ::apollo::common::util::FindOrNull;
44
using ::apollo::common::PathPoint;
45 46
using ::apollo::hdmap::LaneInfo;
using ::apollo::perception::PerceptionObstacle;
47

48 49 50
namespace {

double Damp(const double x, const double sigma) {
K
kechxu 已提交
51
  return 1 / (1 + exp(1 / (std::fabs(x) + sigma)));
52 53 54 55
}

}  // namespace

56 57
Obstacle::Obstacle() {
  double heading_filter_param = FLAGS_heading_filter_param;
58 59
  CHECK_LT(heading_filter_param, 1.0);
  CHECK_GT(heading_filter_param, 0.0);
60 61 62 63
  heading_filter_ = common::DigitalFilter{{1.0, 1.0 - heading_filter_param},
                                          {heading_filter_param}};
}

D
Dong Li 已提交
64
PerceptionObstacle::Type Obstacle::type() const { return type_; }
65

66
int Obstacle::id() const { return id_; }
K
Kecheng Xu 已提交
67 68 69 70 71 72 73 74 75

double Obstacle::timestamp() const {
  if (feature_history_.size() > 0) {
    return feature_history_.front().timestamp();
  } else {
    return 0.0;
  }
}

K
kechxu 已提交
76
const Feature& Obstacle::feature(size_t i) const {
K
Kecheng Xu 已提交
77 78 79 80 81 82 83 84 85
  CHECK(i < feature_history_.size());
  return feature_history_[i];
}

Feature* Obstacle::mutable_feature(size_t i) {
  CHECK(i < feature_history_.size());
  return &feature_history_[i];
}

K
kechxu 已提交
86
const Feature& Obstacle::latest_feature() const {
C
Calvin Miao 已提交
87
  CHECK_GT(feature_history_.size(), 0);
K
Kecheng Xu 已提交
88 89 90 91
  return feature_history_.front();
}

Feature* Obstacle::mutable_latest_feature() {
C
Calvin Miao 已提交
92
  CHECK_GT(feature_history_.size(), 0);
K
Kecheng Xu 已提交
93 94 95
  return &(feature_history_.front());
}

96
size_t Obstacle::history_size() const { return feature_history_.size(); }
K
Kecheng Xu 已提交
97

K
kechxu 已提交
98
const KalmanFilter<double, 6, 2, 0>& Obstacle::kf_motion_tracker() const {
C
Calvin Miao 已提交
99 100 101
  return kf_motion_tracker_;
}

K
kechxu 已提交
102
const KalmanFilter<double, 2, 2, 4>& Obstacle::kf_pedestrian_tracker() const {
103 104 105
  return kf_pedestrian_tracker_;
}

106 107 108 109 110 111 112
bool Obstacle::IsStill() {
  if (feature_history_.size() > 0) {
    return feature_history_.front().is_still();
  }
  return true;
}

113 114 115
bool Obstacle::IsOnLane() {
  if (feature_history_.size() > 0) {
    if (feature_history_.front().has_lane() &&
116 117
        (feature_history_.front().lane().current_lane_feature_size() > 0 ||
         feature_history_.front().lane().nearby_lane_feature_size() > 0)) {
K
kechxu 已提交
118
      ADEBUG << "Obstacle [" << id_ << "] is on lane.";
119 120 121
      return true;
    }
  }
K
kechxu 已提交
122
  ADEBUG << "Obstacle [" << id_ << "] is not on lane.";
123 124 125
  return false;
}

C
Calvin Miao 已提交
126 127 128 129 130 131
bool Obstacle::IsNearJunction() {
  if (feature_history_.size() <= 0) {
    return false;
  }
  double pos_x = latest_feature().position().x();
  double pos_y = latest_feature().position().y();
132 133
  return PredictionMap::NearJunction({pos_x, pos_y},
                                     FLAGS_junction_search_radius);
C
Calvin Miao 已提交
134 135
}

136
void Obstacle::Insert(const PerceptionObstacle& perception_obstacle,
137
                      const double timestamp) {
138
  if (feature_history_.size() > 0 &&
139 140 141
      timestamp <= feature_history_.front().timestamp()) {
    AERROR << "Obstacle [" << id_ << "] received an older frame ["
           << std::setprecision(20) << timestamp
K
kechxu 已提交
142 143
           << "] than the most recent timestamp [ "
           << feature_history_.front().timestamp() << "].";
144 145 146 147 148 149 150
    return;
  }

  Feature feature;
  if (SetId(perception_obstacle, &feature) == ErrorCode::PREDICTION_ERROR) {
    return;
  }
151
  if (SetType(perception_obstacle, &feature) == ErrorCode::PREDICTION_ERROR) {
152 153
    return;
  }
C
Calvin Miao 已提交
154 155 156 157

  // Set obstacle observation for KF tracking
  SetStatus(perception_obstacle, timestamp, &feature);

158 159 160 161 162 163 164 165 166 167 168
  if (!FLAGS_use_navigation_mode) {
    // Update KF
    if (!kf_motion_tracker_.IsInitialized()) {
      InitKFMotionTracker(feature);
    }
    UpdateKFMotionTracker(feature);
    if (type_ == PerceptionObstacle::PEDESTRIAN) {
      if (!kf_pedestrian_tracker_.IsInitialized()) {
        InitKFPedestrianTracker(feature);
      }
      UpdateKFPedestrianTracker(feature);
C
Calvin Miao 已提交
169 170
    }

171 172 173 174
    // Update obstacle status based on KF if enabled
    if (FLAGS_enable_kf_tracking) {
      UpdateStatus(&feature);
    }
C
Calvin Miao 已提交
175 176 177
  }

  // Set obstacle lane features
178 179
  SetCurrentLanes(&feature);
  SetNearbyLanes(&feature);
180
  SetLaneGraphFeature(&feature);
C
Calvin Miao 已提交
181 182 183 184 185

  // Insert obstacle feature to history
  InsertFeatureToHistory(feature);

  // Set obstacle motion status
186 187 188 189 190
  if (FLAGS_use_navigation_mode) {
    SetMotionStatusBySpeed();
  } else {
    SetMotionStatus();
  }
C
Calvin Miao 已提交
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

  // Trim historical features
  Trim();
}

void Obstacle::SetStatus(const PerceptionObstacle& perception_obstacle,
                         const double timestamp, Feature* feature) {
  SetTimestamp(perception_obstacle, timestamp, feature);
  SetPosition(perception_obstacle, feature);
  SetVelocity(perception_obstacle, feature);
  SetAcceleration(feature);
  SetTheta(perception_obstacle, feature);
  SetLengthWidthHeight(perception_obstacle, feature);
}

void Obstacle::UpdateStatus(Feature* feature) {
  // Update motion belief
  if (!kf_motion_tracker_.IsInitialized()) {
    ADEBUG << "Obstacle [" << id_ << "] has not initialized motion tracker.";
    return;
  }
  auto state = kf_motion_tracker_.GetStateEstimate();

  feature->mutable_t_position()->set_x(state(0, 0));
  feature->mutable_t_position()->set_y(state(1, 0));
  feature->mutable_t_position()->set_z(feature->position().z());

  double velocity_x = state(2, 0);
  double velocity_y = state(3, 0);
  double speed = std::hypot(velocity_x, velocity_y);
  double velocity_heading = std::atan2(velocity_y, velocity_x);
222
  if (FLAGS_adjust_velocity_by_position_shift) {
C
Calvin Miao 已提交
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
    UpdateVelocity(feature->theta(), &velocity_x, &velocity_y,
                   &velocity_heading, &speed);
  }
  feature->mutable_velocity()->set_x(velocity_x);
  feature->mutable_velocity()->set_y(velocity_y);
  feature->mutable_velocity()->set_z(velocity_heading);
  feature->set_speed(speed);
  feature->set_velocity_heading(std::atan2(state(3, 0), state(2, 0)));

  double acc_x = common::math::Clamp(state(4, 0), FLAGS_min_acc, FLAGS_max_acc);
  double acc_y = common::math::Clamp(state(5, 0), FLAGS_min_acc, FLAGS_max_acc);
  double acc =
      acc_x * std::cos(velocity_heading) + acc_y * std::sin(velocity_heading);
  feature->mutable_acceleration()->set_x(acc_x);
  feature->mutable_acceleration()->set_y(acc_y);
  feature->mutable_acceleration()->set_z(feature->acceleration().z());
  feature->set_acc(acc);

  ADEBUG << "Obstacle [" << id_ << "] has tracked position [" << std::fixed
         << std::setprecision(6) << feature->t_position().x() << ", "
         << std::fixed << std::setprecision(6) << feature->t_position().y()
         << ", " << std::fixed << std::setprecision(6)
         << feature->t_position().z() << "]";
  ADEBUG << "Obstacle [" << id_ << "] has tracked velocity [" << std::fixed
         << std::setprecision(6) << feature->velocity().x() << ", "
         << std::fixed << std::setprecision(6) << feature->velocity().y()
         << ", " << std::fixed << std::setprecision(6)
         << feature->velocity().z() << "]";
  ADEBUG << "Obstacle [" << id_ << "] has tracked acceleration [" << std::fixed
         << std::setprecision(6) << feature->acceleration().x() << ", "
         << std::fixed << std::setprecision(6) << feature->acceleration().y()
         << ", " << std::fixed << std::setprecision(6)
         << feature->acceleration().z() << "]";
  ADEBUG << "Obstacle [" << id_ << "] has tracked velocity heading ["
         << std::fixed << std::setprecision(6) << feature->velocity_heading()
         << "].";

  // Update pedestrian motion belief
261
  if (type_ == PerceptionObstacle::PEDESTRIAN) {
C
Calvin Miao 已提交
262
    if (!kf_pedestrian_tracker_.IsInitialized()) {
C
Calvin Miao 已提交
263 264 265
      ADEBUG << "Obstacle [" << id_
             << "] has not initialized pedestrian tracker.";
      return;
266
    }
C
Calvin Miao 已提交
267 268 269 270 271 272 273 274 275
    feature->mutable_t_position()->set_x(
        kf_pedestrian_tracker_.GetStateEstimate()(0, 0));
    feature->mutable_t_position()->set_y(
        kf_pedestrian_tracker_.GetStateEstimate()(1, 0));
    ADEBUG << "Obstacle [" << id_ << "] has tracked pedestrian position ["
           << std::setprecision(6) << feature->t_position().x() << std::fixed
           << ", " << std::setprecision(6) << feature->t_position().y()
           << std::fixed << ", " << std::setprecision(6)
           << feature->t_position().z() << std::fixed << "]";
276
  }
277 278 279 280 281 282 283 284 285 286 287 288
}

ErrorCode Obstacle::SetId(const PerceptionObstacle& perception_obstacle,
                          Feature* feature) {
  if (!perception_obstacle.has_id()) {
    AERROR << "Obstacle has no ID.";
    return ErrorCode::PREDICTION_ERROR;
  }

  int id = perception_obstacle.id();
  if (id_ < 0) {
    id_ = id;
289
    ADEBUG << "Obstacle has id [" << id_ << "].";
290 291 292 293 294 295 296 297 298 299 300
  } else {
    if (id_ != id) {
      AERROR << "Obstacle [" << id_ << "] has a mismatched ID [" << id
             << "] from perception obstacle.";
      return ErrorCode::PREDICTION_ERROR;
    } else {
    }
  }
  return ErrorCode::OK;
}

301 302
ErrorCode Obstacle::SetType(const PerceptionObstacle& perception_obstacle,
                            Feature* feature) {
303 304
  if (perception_obstacle.has_type()) {
    type_ = perception_obstacle.type();
305
    ADEBUG << "Obstacle [" << id_ << "] has type [" << type_ << "].";
306
    feature->set_type(type_);
307 308 309 310 311 312
  } else {
    AERROR << "Obstacle [" << id_ << "] has no type.";
    return ErrorCode::PREDICTION_ERROR;
  }
  return ErrorCode::OK;
}
K
kechxu 已提交
313

314 315 316 317 318 319 320 321 322
void Obstacle::SetTimestamp(const PerceptionObstacle& perception_obstacle,
                            const double timestamp, Feature* feature) {
  double ts = timestamp;
  if (perception_obstacle.has_timestamp() &&
      perception_obstacle.timestamp() > 0.0) {
    ts = perception_obstacle.timestamp();
  }
  feature->set_timestamp(ts);

D
Dong Li 已提交
323 324
  ADEBUG << "Obstacle [" << id_ << "] has timestamp [" << std::fixed
         << std::setprecision(6) << ts << "].";
K
kechxu 已提交
325 326
}

327 328 329 330
void Obstacle::SetPosition(const PerceptionObstacle& perception_obstacle,
                           Feature* feature) {
  double x = 0.0;
  double y = 0.0;
331
  double z = 0.0;
332 333 334 335 336 337 338 339

  if (perception_obstacle.has_position()) {
    if (perception_obstacle.position().has_x()) {
      x = perception_obstacle.position().x();
    }
    if (perception_obstacle.position().has_y()) {
      y = perception_obstacle.position().y();
    }
340
    if (perception_obstacle.position().has_z()) {
C
Calvin Miao 已提交
341
      z = perception_obstacle.position().z();
342
    }
343 344 345 346
  }

  feature->mutable_position()->set_x(x);
  feature->mutable_position()->set_y(y);
347
  feature->mutable_position()->set_z(z);
348

349
  ADEBUG << "Obstacle [" << id_ << "] has position [" << std::fixed
K
kechxu 已提交
350 351 352
         << std::setprecision(6) << x << ", " << std::fixed
         << std::setprecision(6) << y << ", " << std::fixed
         << std::setprecision(6) << z << "].";
353 354
}

355 356
void Obstacle::SetVelocity(const PerceptionObstacle& perception_obstacle,
                           Feature* feature) {
357 358 359
  double velocity_x = 0.0;
  double velocity_y = 0.0;
  double velocity_z = 0.0;
360 361 362

  if (perception_obstacle.has_velocity()) {
    if (perception_obstacle.velocity().has_x()) {
363
      velocity_x = perception_obstacle.velocity().x();
364 365
    }
    if (perception_obstacle.velocity().has_y()) {
366 367 368 369
      velocity_y = perception_obstacle.velocity().y();
    }
    if (perception_obstacle.velocity().has_z()) {
      velocity_z = perception_obstacle.velocity().z();
370 371
    }
  }
K
kechxu 已提交
372

C
Calvin Miao 已提交
373
  double speed = std::hypot(velocity_x, velocity_y);
374 375 376 377
  double velocity_heading = std::atan2(velocity_y, velocity_x);
  if (FLAGS_adjust_velocity_by_obstacle_heading) {
    velocity_heading = perception_obstacle.theta();
  }
C
Calvin Miao 已提交
378

379 380
  if (!FLAGS_use_navigation_mode &&
      FLAGS_adjust_velocity_by_position_shift &&
D
Dong Li 已提交
381
      history_size() > 0) {
C
Calvin Miao 已提交
382 383 384 385
    double diff_x =
        feature->position().x() - feature_history_.front().position().x();
    double diff_y =
        feature->position().y() - feature_history_.front().position().y();
K
kechxu 已提交
386 387
    double prev_obstacle_size = std::max(feature_history_.front().length(),
                                         feature_history_.front().width());
388 389
    double obstacle_size =
        std::max(perception_obstacle.length(), perception_obstacle.width());
K
kechxu 已提交
390
    double size_diff = std::abs(obstacle_size - prev_obstacle_size);
391 392 393
    double shift_thred =
        std::max(obstacle_size * FLAGS_valid_position_diff_rate_threshold,
                 FLAGS_valid_position_diff_threshold);
K
kechxu 已提交
394 395 396 397
    double size_diff_thred =
        FLAGS_split_rate * std::min(obstacle_size, prev_obstacle_size);
    if (std::fabs(diff_x) > shift_thred && std::fabs(diff_y) > shift_thred &&
        size_diff < size_diff_thred) {
K
kechxu 已提交
398
      double shift_heading = std::atan2(diff_y, diff_x);
C
Calvin Miao 已提交
399
      double angle_diff = ::apollo::common::math::NormalizeAngle(
K
kechxu 已提交
400 401
          shift_heading - velocity_heading);
      if (std::fabs(angle_diff) > FLAGS_max_lane_angle_diff) {
402
        ADEBUG << "Shift velocity heading to be " << shift_heading;
K
kechxu 已提交
403 404
        velocity_heading = shift_heading;
      }
405
    }
406 407
    double filtered_heading = heading_filter_.Filter(velocity_heading);
    if (type_ == PerceptionObstacle::BICYCLE ||
D
Dong Li 已提交
408
        type_ == PerceptionObstacle::PEDESTRIAN) {
409 410
      velocity_heading = filtered_heading;
    }
K
kechxu 已提交
411 412
    velocity_x = speed * std::cos(velocity_heading);
    velocity_y = speed * std::sin(velocity_heading);
413
  }
414

415 416 417
  feature->mutable_velocity()->set_x(velocity_x);
  feature->mutable_velocity()->set_y(velocity_y);
  feature->mutable_velocity()->set_z(velocity_z);
418 419 420
  feature->set_velocity_heading(velocity_heading);
  feature->set_speed(speed);

D
Dong Li 已提交
421 422 423 424 425 426 427 428
  ADEBUG << "Obstacle [" << id_ << "] has velocity [" << std::fixed
         << std::setprecision(6) << velocity_x << ", " << std::fixed
         << std::setprecision(6) << velocity_y << ", " << std::fixed
         << std::setprecision(6) << velocity_z << "]";
  ADEBUG << "Obstacle [" << id_ << "] has velocity heading [" << std::fixed
         << std::setprecision(6) << velocity_heading << "] ";
  ADEBUG << "Obstacle [" << id_ << "] has speed [" << std::fixed
         << std::setprecision(6) << speed << "].";
429
}
430

C
Calvin Miao 已提交
431 432 433 434 435 436 437 438 439 440 441 442 443
void Obstacle::UpdateVelocity(const double theta, double* velocity_x,
                              double* velocity_y, double* velocity_heading,
                              double* speed) {
  *speed = std::hypot(*velocity_x, *velocity_y);
  double angle_diff =
      ::apollo::common::math::NormalizeAngle(*velocity_heading - theta);
  if (std::fabs(angle_diff) <= FLAGS_max_lane_angle_diff) {
    *velocity_heading = theta;
    *velocity_x = *speed * std::cos(*velocity_heading);
    *velocity_y = *speed * std::sin(*velocity_heading);
  }
}

444 445 446 447
void Obstacle::SetAcceleration(Feature* feature) {
  double acc_x = 0.0;
  double acc_y = 0.0;
  double acc_z = 0.0;
K
kechxu 已提交
448
  double acc = 0.0;
449 450 451 452 453 454 455 456

  if (feature_history_.size() > 0) {
    double curr_ts = feature->timestamp();
    double prev_ts = feature_history_.front().timestamp();

    const Point3D& curr_velocity = feature->velocity();
    const Point3D& prev_velocity = feature_history_.front().velocity();

457
    if (curr_ts > prev_ts) {
C
Calvin Miao 已提交
458 459 460 461
      /*
       * A damp function is to punish acc calculation for low speed
       * and reward it for high speed
       */
462 463 464 465 466 467 468
      double damping_x = Damp(curr_velocity.x(), 0.001);
      double damping_y = Damp(curr_velocity.y(), 0.001);
      double damping_z = Damp(curr_velocity.z(), 0.001);

      acc_x = (curr_velocity.x() - prev_velocity.x()) / (curr_ts - prev_ts);
      acc_y = (curr_velocity.y() - prev_velocity.y()) / (curr_ts - prev_ts);
      acc_z = (curr_velocity.z() - prev_velocity.z()) / (curr_ts - prev_ts);
K
kechxu 已提交
469

K
kechxu 已提交
470 471 472 473
      acc_x *= damping_x;
      acc_y *= damping_y;
      acc_z *= damping_z;

C
Calvin Miao 已提交
474 475 476 477 478 479 480
      acc_x =
          common::math::Clamp(acc_x * damping_x, FLAGS_min_acc, FLAGS_max_acc);
      acc_y =
          common::math::Clamp(acc_y * damping_y, FLAGS_min_acc, FLAGS_max_acc);
      acc_z =
          common::math::Clamp(acc_z * damping_z, FLAGS_min_acc, FLAGS_max_acc);

K
kechxu 已提交
481 482
      double heading = feature->velocity_heading();
      acc = acc_x * std::cos(heading) + acc_y * std::sin(heading);
483 484 485 486 487 488 489 490
    }
  }

  feature->mutable_acceleration()->set_x(acc_x);
  feature->mutable_acceleration()->set_y(acc_y);
  feature->mutable_acceleration()->set_z(acc_z);
  feature->set_acc(acc);

D
Dong Li 已提交
491 492 493 494 495 496
  ADEBUG << "Obstacle [" << id_ << "] has acceleration [" << std::fixed
         << std::setprecision(6) << acc_x << ", " << std::fixed
         << std::setprecision(6) << acc_y << ", " << std::fixed
         << std::setprecision(6) << acc_z << "]";
  ADEBUG << "Obstacle [" << id_ << "] has acceleration value [" << std::fixed
         << std::setprecision(6) << acc << "].";
497 498 499 500 501 502 503 504 505 506
}

void Obstacle::SetTheta(const PerceptionObstacle& perception_obstacle,
                        Feature* feature) {
  double theta = 0.0;
  if (perception_obstacle.has_theta()) {
    theta = perception_obstacle.theta();
  }
  feature->set_theta(theta);

D
Dong Li 已提交
507 508
  ADEBUG << "Obstacle [" << id_ << "] has theta [" << std::fixed
         << std::setprecision(6) << theta << "].";
K
kechxu 已提交
509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530
}

void Obstacle::SetLengthWidthHeight(
    const PerceptionObstacle& perception_obstacle, Feature* feature) {
  double length = 0.0;
  double width = 0.0;
  double height = 0.0;

  if (perception_obstacle.has_length()) {
    length = perception_obstacle.length();
  }
  if (perception_obstacle.has_width()) {
    width = perception_obstacle.width();
  }
  if (perception_obstacle.has_height()) {
    height = perception_obstacle.height();
  }

  feature->set_length(length);
  feature->set_width(width);
  feature->set_height(height);

531
  ADEBUG << "Obstacle [" << id_ << "] has dimension [" << std::fixed
K
kechxu 已提交
532 533 534 535 536
         << std::setprecision(6) << length << ", " << std::fixed
         << std::setprecision(6) << width << ", " << std::fixed
         << std::setprecision(6) << height << "].";
}

C
Calvin Miao 已提交
537
void Obstacle::InitKFMotionTracker(const Feature& feature) {
K
kechxu 已提交
538
  // Set transition matrix F
539
  // constant acceleration dynamic model
K
kechxu 已提交
540
  Eigen::Matrix<double, 6, 6> F;
C
Calvin Miao 已提交
541
  F.setIdentity();
K
kechxu 已提交
542 543 544 545
  kf_motion_tracker_.SetTransitionMatrix(F);

  // Set observation matrix H
  Eigen::Matrix<double, 2, 6> H;
C
Calvin Miao 已提交
546
  H.setIdentity();
K
kechxu 已提交
547 548 549
  kf_motion_tracker_.SetObservationMatrix(H);

  // Set covariance of transition noise matrix Q
550 551
  // make the noise this order:
  // noise(x/y) < noise(vx/vy) < noise(ax/ay)
K
kechxu 已提交
552 553 554 555 556 557 558 559 560 561 562 563
  Eigen::Matrix<double, 6, 6> Q;
  Q.setIdentity();
  Q *= FLAGS_q_var;
  kf_motion_tracker_.SetTransitionNoise(Q);

  // Set observation noise matrix R
  Eigen::Matrix<double, 2, 2> R;
  R.setIdentity();
  R *= FLAGS_r_var;
  kf_motion_tracker_.SetObservationNoise(R);

  // Set current state covariance matrix P
564 565
  // make the covariance this order:
  // cov(x/y) < cov(vx/vy) < cov(ax/ay)
K
kechxu 已提交
566 567 568 569
  Eigen::Matrix<double, 6, 6> P;
  P.setIdentity();
  P *= FLAGS_p_var;

570 571
  // Set initial state
  Eigen::Matrix<double, 6, 1> x;
C
Calvin Miao 已提交
572 573 574 575 576 577
  x(0, 0) = feature.position().x();
  x(1, 0) = feature.position().y();
  x(2, 0) = feature.velocity().x();
  x(3, 0) = feature.velocity().y();
  x(4, 0) = feature.acceleration().x();
  x(5, 0) = feature.acceleration().y();
578 579

  kf_motion_tracker_.SetStateEstimate(x, P);
580 581
}

C
Calvin Miao 已提交
582
void Obstacle::UpdateKFMotionTracker(const Feature& feature) {
C
Calvin Miao 已提交
583
  double delta_ts = 0.0;
584
  if (feature_history_.size() > 0) {
C
Calvin Miao 已提交
585
    delta_ts = feature.timestamp() - feature_history_.front().timestamp();
K
kechxu 已提交
586
  }
587
  if (delta_ts > FLAGS_double_precision) {
K
kechxu 已提交
588 589 590
    // Set tansition matrix and predict
    auto F = kf_motion_tracker_.GetTransitionMatrix();
    F(0, 2) = delta_ts;
C
Calvin Miao 已提交
591 592
    F(0, 4) = 0.5 * delta_ts * delta_ts;
    F(1, 3) = delta_ts;
K
kechxu 已提交
593 594 595 596 597 598 599 600
    F(1, 5) = 0.5 * delta_ts * delta_ts;
    F(2, 4) = delta_ts;
    F(3, 5) = delta_ts;
    kf_motion_tracker_.SetTransitionMatrix(F);
    kf_motion_tracker_.Predict();

    // Set observation and correct
    Eigen::Matrix<double, 2, 1> z;
C
Calvin Miao 已提交
601 602
    z(0, 0) = feature.position().x();
    z(1, 0) = feature.position().y();
K
kechxu 已提交
603
    kf_motion_tracker_.Correct(z);
604
  }
K
kechxu 已提交
605 606
}

C
Calvin Miao 已提交
607
void Obstacle::InitKFPedestrianTracker(const Feature& feature) {
608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641
  // Set transition matrix F
  Eigen::Matrix<double, 2, 2> F;
  F.setIdentity();
  kf_pedestrian_tracker_.SetTransitionMatrix(F);

  // Set observation matrix H
  Eigen::Matrix<double, 2, 2> H;
  H.setIdentity();
  kf_pedestrian_tracker_.SetObservationMatrix(H);

  // Set control matrix
  Eigen::Matrix<double, 2, 4> B;
  B.setZero();
  kf_pedestrian_tracker_.SetControlMatrix(B);

  // Set covariance of transition noise matrix Q
  Eigen::Matrix<double, 2, 2> Q;
  Q.setIdentity();
  Q *= FLAGS_q_var;
  kf_pedestrian_tracker_.SetTransitionNoise(Q);

  // Set observation noise matrix R
  Eigen::Matrix<double, 2, 2> R;
  R.setIdentity();
  R *= FLAGS_r_var;
  kf_pedestrian_tracker_.SetObservationNoise(R);

  // Set current state covariance matrix P
  Eigen::Matrix<double, 2, 2> P;
  P.setIdentity();
  P *= FLAGS_p_var;

  // Set initial state
  Eigen::Matrix<double, 2, 1> x;
642
  x.setZero();
C
Calvin Miao 已提交
643 644
  x(0, 0) = feature.position().x();
  x(1, 0) = feature.position().y();
645 646 647 648

  kf_pedestrian_tracker_.SetStateEstimate(x, P);
}

C
Calvin Miao 已提交
649
void Obstacle::UpdateKFPedestrianTracker(const Feature& feature) {
650 651
  double delta_ts = 0.0;
  if (!feature_history_.empty()) {
C
Calvin Miao 已提交
652
    delta_ts = feature.timestamp() - feature_history_.front().timestamp();
653
  }
K
kechxu 已提交
654 655 656 657 658 659 660 661 662 663
  if (delta_ts > std::numeric_limits<double>::epsilon()) {
    Eigen::Matrix<double, 2, 4> B = kf_pedestrian_tracker_.GetControlMatrix();
    B(0, 0) = delta_ts;
    B(0, 2) = 0.5 * delta_ts * delta_ts;
    B(1, 1) = delta_ts;
    B(1, 3) = 0.5 * delta_ts * delta_ts;
    kf_pedestrian_tracker_.SetControlMatrix(B);

    // Set control vector
    Eigen::Matrix<double, 4, 1> u;
C
Calvin Miao 已提交
664 665
    u(0, 0) = feature.velocity().x();
    u(1, 0) = feature.velocity().y();
K
kechxu 已提交
666
    if (FLAGS_enable_pedestrian_acc) {
C
Calvin Miao 已提交
667 668
      u(2, 0) = feature.acceleration().x();
      u(3, 0) = feature.acceleration().y();
K
kechxu 已提交
669
    }
670

K
kechxu 已提交
671
    kf_pedestrian_tracker_.Predict(u);
672

K
kechxu 已提交
673 674
    // Set observation vector
    Eigen::Matrix<double, 2, 1> z;
C
Calvin Miao 已提交
675 676
    z(0, 0) = feature.position().x();
    z(1, 0) = feature.position().y();
K
kechxu 已提交
677 678
    kf_pedestrian_tracker_.Correct(z);
  }
679 680
}

681
void Obstacle::SetCurrentLanes(Feature* feature) {
682
  Eigen::Vector2d point(feature->position().x(), feature->position().y());
683
  double heading = feature->velocity_heading();
K
kechxu 已提交
684 685 686 687 688 689 690 691
  int max_num_lane = FLAGS_max_num_current_lane;
  double max_angle_diff = FLAGS_max_lane_angle_diff;
  double lane_search_radius = FLAGS_lane_search_radius;
  if (PredictionMap::InJunction(point, FLAGS_junction_search_radius)) {
    max_num_lane = FLAGS_max_num_current_lane_in_junction;
    max_angle_diff = FLAGS_max_lane_angle_diff_in_junction;
    lane_search_radius = FLAGS_lane_search_radius_in_junction;
  }
692
  std::vector<std::shared_ptr<const LaneInfo>> current_lanes;
693
  PredictionMap::OnLane(current_lanes_, point, heading,
K
kechxu 已提交
694 695
                        lane_search_radius, true, max_num_lane,
                        max_angle_diff, &current_lanes);
696 697
  current_lanes_ = current_lanes;
  if (current_lanes_.empty()) {
698
    ADEBUG << "Obstacle [" << id_ << "] has no current lanes.";
699 700 701 702 703 704 705
    return;
  }
  Lane lane;
  if (feature->has_lane()) {
    lane = feature->lane();
  }
  double min_heading_diff = std::numeric_limits<double>::infinity();
706
  for (std::shared_ptr<const LaneInfo> current_lane : current_lanes) {
C
Calvin Miao 已提交
707 708 709 710
    if (current_lane == nullptr) {
      continue;
    }

711
    int turn_type = PredictionMap::LaneTurnType(current_lane->id().id());
712 713 714
    std::string lane_id = current_lane->id().id();
    double s = 0.0;
    double l = 0.0;
715
    PredictionMap::GetProjection(point, current_lane, &s, &l);
C
Calvin Miao 已提交
716 717 718
    if (s < 0.0) {
      continue;
    }
C
Calvin Miao 已提交
719

720
    common::math::Vec2d vec_point(point[0], point[1]);
721
    double distance = 0.0;
722
    common::PointENU nearest_point =
723
        current_lane->GetNearestPoint(vec_point, &distance);
724
    double nearest_point_heading =
725
        PredictionMap::PathHeading(current_lane, nearest_point);
726
    double angle_diff = common::math::AngleDiff(heading, nearest_point_heading);
727 728
    double left = 0.0;
    double right = 0.0;
729
    current_lane->GetWidth(s, &left, &right);
730 731 732 733 734 735 736 737 738 739 740 741
    LaneFeature* lane_feature = lane.add_current_lane_feature();
    lane_feature->set_lane_turn_type(turn_type);
    lane_feature->set_lane_id(lane_id);
    lane_feature->set_lane_s(s);
    lane_feature->set_lane_l(l);
    lane_feature->set_angle_diff(angle_diff);
    lane_feature->set_dist_to_left_boundary(left - l);
    lane_feature->set_dist_to_right_boundary(right + l);
    if (std::fabs(angle_diff) < min_heading_diff) {
      lane.mutable_lane_feature()->CopyFrom(*lane_feature);
      min_heading_diff = std::fabs(angle_diff);
    }
C
Calvin Miao 已提交
742 743
    ADEBUG << "Obstacle [" << id_ << "] has current lanes ["
           << lane_feature->ShortDebugString() << "].";
744 745 746 747
  }

  if (lane.has_lane_feature()) {
    ADEBUG << "Obstacle [" << id_ << "] has one current lane ["
C
Calvin Miao 已提交
748
           << lane.lane_feature().ShortDebugString() << "].";
749 750 751
  }

  feature->mutable_lane()->CopyFrom(lane);
752 753 754
}

void Obstacle::SetNearbyLanes(Feature* feature) {
755
  Eigen::Vector2d point(feature->position().x(), feature->position().y());
K
kechxu 已提交
756 757 758 759
  int max_num_lane = FLAGS_max_num_nearby_lane;
  if (PredictionMap::InJunction(point, FLAGS_junction_search_radius)) {
    max_num_lane = FLAGS_max_num_nearby_lane_in_junction;
  }
760
  double theta = feature->velocity_heading();
761
  std::vector<std::shared_ptr<const LaneInfo>> nearby_lanes;
762
  PredictionMap::NearbyLanesByCurrentLanes(
K
kechxu 已提交
763 764
      point, theta, FLAGS_lane_search_radius, current_lanes_,
      max_num_lane, &nearby_lanes);
765
  if (nearby_lanes.empty()) {
K
kechxu 已提交
766
    ADEBUG << "Obstacle [" << id_ << "] has no nearby lanes.";
767 768 769
    return;
  }

770
  for (std::shared_ptr<const LaneInfo> nearby_lane : nearby_lanes) {
771 772 773
    if (nearby_lane == nullptr) {
      continue;
    }
774 775 776 777 778 779 780 781 782 783

    // Ignore bike and sidewalk lanes for vehicles
    if (type_ == PerceptionObstacle::VEHICLE &&
        nearby_lane->lane().has_type() &&
        (nearby_lane->lane().type() == ::apollo::hdmap::Lane::BIKING ||
         nearby_lane->lane().type() == ::apollo::hdmap::Lane::SIDEWALK)) {
      ADEBUG << "Obstacle [" << id_ << "] ignores disqualified lanes.";
      continue;
    }

784 785
    double s = -1.0;
    double l = 0.0;
786
    PredictionMap::GetProjection(point, nearby_lane, &s, &l);
787 788 789
    if (s < 0.0 || s >= nearby_lane->total_length()) {
      continue;
    }
790
    int turn_type = PredictionMap::LaneTurnType(nearby_lane->id().id());
C
Calvin Miao 已提交
791
    double heading = feature->velocity_heading();
792
    double angle_diff = 0.0;
793
    hdmap::MapPathPoint nearest_point;
794
    if (!PredictionMap::ProjectionFromLane(nearby_lane, s, &nearest_point)) {
795
      angle_diff = common::math::AngleDiff(nearest_point.heading(), heading);
796 797 798 799
    }

    double left = 0.0;
    double right = 0.0;
800
    nearby_lane->GetWidth(s, &left, &right);
801 802 803 804 805 806 807 808 809 810 811

    LaneFeature* lane_feature =
        feature->mutable_lane()->add_nearby_lane_feature();

    lane_feature->set_lane_turn_type(turn_type);
    lane_feature->set_lane_id(nearby_lane->id().id());
    lane_feature->set_lane_s(s);
    lane_feature->set_lane_l(l);
    lane_feature->set_angle_diff(angle_diff);
    lane_feature->set_dist_to_left_boundary(left - l);
    lane_feature->set_dist_to_right_boundary(right + l);
C
Calvin Miao 已提交
812 813
    ADEBUG << "Obstacle [" << id_ << "] has nearby lanes ["
           << lane_feature->ShortDebugString() << "]";
814
  }
815 816
}

817
void Obstacle::SetLaneGraphFeature(Feature* feature) {
818
  double speed = feature->speed();
819
  double road_graph_distance = std::max(
820
      speed * FLAGS_prediction_duration +
821 822
      0.5 * FLAGS_max_acc * FLAGS_prediction_duration *
      FLAGS_prediction_duration, FLAGS_min_prediction_length);
823 824

  int seq_id = 0;
825
  int curr_lane_count = 0;
826
  for (auto& lane : feature->lane().current_lane_feature()) {
827 828
    std::shared_ptr<const LaneInfo> lane_info =
        PredictionMap::LaneById(lane.lane_id());
829
    const LaneGraph& lane_graph = ObstacleClusters::GetLaneGraph(
830
        lane.lane_s(), road_graph_distance, lane_info);
831 832 833
    if (lane_graph.lane_sequence_size() > 0) {
      ++curr_lane_count;
    }
C
Calvin Miao 已提交
834
    for (const auto& lane_seq : lane_graph.lane_sequence()) {
835 836
      LaneSequence seq(lane_seq);
      seq.set_lane_sequence_id(seq_id++);
D
Dong Li 已提交
837
      feature->mutable_lane()
838 839
          ->mutable_lane_graph()
          ->add_lane_sequence()
840
          ->CopyFrom(seq);
C
Calvin Miao 已提交
841 842
      ADEBUG << "Obstacle [" << id_ << "] set a lane sequence ["
             << lane_seq.ShortDebugString() << "].";
843
    }
844 845 846
    if (curr_lane_count >= FLAGS_max_num_current_lane) {
      break;
    }
847
  }
848 849

  int nearby_lane_count = 0;
850
  for (auto& lane : feature->lane().nearby_lane_feature()) {
851 852
    std::shared_ptr<const LaneInfo> lane_info =
        PredictionMap::LaneById(lane.lane_id());
853
    const LaneGraph& lane_graph = ObstacleClusters::GetLaneGraph(
854
        lane.lane_s(), road_graph_distance, lane_info);
855 856 857
    if (lane_graph.lane_sequence_size() > 0) {
      ++nearby_lane_count;
    }
C
Calvin Miao 已提交
858
    for (const auto& lane_seq : lane_graph.lane_sequence()) {
859 860
      LaneSequence seq(lane_seq);
      seq.set_lane_sequence_id(seq_id++);
D
Dong Li 已提交
861
      feature->mutable_lane()
862 863
          ->mutable_lane_graph()
          ->add_lane_sequence()
864
          ->CopyFrom(seq);
C
Calvin Miao 已提交
865 866
      ADEBUG << "Obstacle [" << id_ << "] set a lane sequence ["
             << lane_seq.ShortDebugString() << "].";
867
    }
868 869 870
    if (nearby_lane_count >= FLAGS_max_num_nearby_lane) {
      break;
    }
871 872
  }

C
Calvin Miao 已提交
873
  if (feature->has_lane() && feature->lane().has_lane_graph()) {
874
    SetLanePoints(feature);
875
    SetLaneSequencePath(feature->mutable_lane()->mutable_lane_graph());
876
  }
K
kechxu 已提交
877

C
Calvin Miao 已提交
878
  ADEBUG << "Obstacle [" << id_ << "] set lane graph features.";
879 880
}

881
void Obstacle::SetLanePoints(Feature* feature) {
882
  if (feature == nullptr || !feature->has_velocity_heading()) {
C
Calvin Miao 已提交
883
    AERROR << "Null feature or no velocity heading.";
884 885 886
    return;
  }

887
  LaneGraph* lane_graph = feature->mutable_lane()->mutable_lane_graph();
C
Calvin Miao 已提交
888
  double heading = feature->velocity_heading();
889 890 891 892 893 894 895 896 897
  double x = feature->position().x();
  double y = feature->position().y();
  Eigen::Vector2d position(x, y);
  for (int i = 0; i < lane_graph->lane_sequence_size(); ++i) {
    LaneSequence* lane_sequence = lane_graph->mutable_lane_sequence(i);
    if (lane_sequence->lane_segment_size() <= 0) {
      continue;
    }
    int lane_index = 0;
898
    LaneSegment* lane_segment = lane_sequence->mutable_lane_segment(lane_index);
899 900
    double start_s = lane_sequence->lane_segment(lane_index).start_s();
    double total_s = 0.0;
901
    double lane_seg_s = start_s;
902 903 904
    std::size_t count_point = 0;
    while (lane_index < lane_sequence->lane_segment_size() &&
           count_point < FLAGS_max_num_lane_point) {
905 906 907 908 909 910 911 912 913 914
      if (lane_seg_s > lane_segment->end_s()) {
        start_s = lane_seg_s - lane_segment->end_s();
        lane_seg_s = start_s;
        ++lane_index;
        if (lane_index < lane_sequence->lane_segment_size()) {
          lane_segment = lane_sequence->mutable_lane_segment(lane_index);
        } else {
          lane_segment = nullptr;
        }
      } else {
915
        std::string lane_id = lane_segment->lane_id();
916 917
        std::shared_ptr<const LaneInfo> lane_info =
            PredictionMap::LaneById(lane_id);
918 919 920 921
        if (lane_info == nullptr) {
          break;
        }
        LanePoint lane_point;
922
        Eigen::Vector2d lane_point_pos =
923 924 925 926 927
            PredictionMap::PositionOnLane(lane_info, lane_seg_s);
        double lane_point_heading =
            PredictionMap::HeadingOnLane(lane_info, lane_seg_s);
        double lane_point_width =
            PredictionMap::LaneTotalWidth(lane_info, lane_seg_s);
928
        double lane_point_angle_diff =
929
            common::math::AngleDiff(lane_point_heading, heading);
930 931 932 933 934 935
        lane_point.mutable_position()->set_x(lane_point_pos[0]);
        lane_point.mutable_position()->set_y(lane_point_pos[1]);
        lane_point.set_heading(lane_point_heading);
        lane_point.set_width(lane_point_width);
        double lane_s = -1.0;
        double lane_l = 0.0;
936
        PredictionMap::GetProjection(position, lane_info, &lane_s, &lane_l);
937 938 939
        lane_point.set_relative_s(total_s);
        lane_point.set_relative_l(0.0 - lane_l);
        lane_point.set_angle_diff(lane_point_angle_diff);
940
        lane_segment->set_lane_turn_type(PredictionMap::LaneTurnType(lane_id));
941
        lane_segment->add_lane_point()->CopyFrom(lane_point);
942
        ++count_point;
943
        total_s += FLAGS_target_lane_gap;
944
        lane_seg_s += FLAGS_target_lane_gap;
945 946 947
      }
    }
  }
948
  ADEBUG << "Obstacle [" << id_ << "] has lane segments and points.";
949 950
}

951 952 953 954 955 956 957 958 959
void Obstacle::SetLaneSequencePath(LaneGraph* const lane_graph) {
  for (int i = 0; i < lane_graph->lane_sequence_size(); ++i) {
    LaneSequence* lane_sequence = lane_graph->mutable_lane_sequence(i);
    double lane_segment_s = 0.0;
    for (int j = 0; j < lane_sequence->lane_segment_size(); ++j) {
      LaneSegment* lane_segment = lane_sequence->mutable_lane_segment(j);
      for (int k = 0; k < lane_segment->lane_point_size(); ++k) {
        LanePoint* lane_point = lane_segment->mutable_lane_point(k);
        PathPoint path_point;
960
        path_point.set_s(lane_point->relative_s());
961 962 963 964 965
        path_point.set_theta(lane_point->heading());
        lane_sequence->add_path_point()->CopyFrom(path_point);
      }
      lane_segment_s += lane_segment->total_length();
    }
966 967 968 969 970 971 972
    int num_path_point = lane_sequence->path_point_size();
    if (num_path_point <= 0) {
      continue;
    }
    for (int j = 0; j + 1 < num_path_point; ++j) {
      PathPoint* first_point = lane_sequence->mutable_path_point(j);
      PathPoint* second_point = lane_sequence->mutable_path_point(j + 1);
973 974
      double delta_theta = apollo::common::math::AngleDiff(
          second_point->theta(), first_point->theta());
975 976 977 978 979
      double delta_s = second_point->s() - first_point->s();
      double kappa = std::abs(delta_theta / (delta_s + FLAGS_double_precision));
      lane_sequence->mutable_path_point(j)->set_kappa(kappa);
    }
    lane_sequence->mutable_path_point(num_path_point - 1)->set_kappa(0.0);
980 981 982
  }
}

983
void Obstacle::SetMotionStatus() {
984 985 986
  int history_size = static_cast<int>(feature_history_.size());
  if (history_size < 2) {
    ADEBUG << "Obstacle [" << id_ << "] has no history and "
987
           << "is considered moving.";
988
    if (history_size > 0) {
989
      feature_history_.front().set_is_still(false);
990 991 992 993 994 995 996 997 998
    }
    return;
  }

  double start_x = 0.0;
  double start_y = 0.0;
  double avg_drift_x = 0.0;
  double avg_drift_y = 0.0;
  int len = std::min(history_size, FLAGS_still_obstacle_history_length);
D
Dong Li 已提交
999
  CHECK_GT(len, 1);
1000 1001

  auto feature_riter = feature_history_.rbegin();
C
Calvin Miao 已提交
1002 1003
  start_x = feature_riter->position().x();
  start_y = feature_riter->position().y();
1004 1005
  ++feature_riter;
  while (feature_riter != feature_history_.rend()) {
C
Calvin Miao 已提交
1006 1007
    avg_drift_x += (feature_riter->position().x() - start_x) / (len - 1);
    avg_drift_y += (feature_riter->position().y() - start_y) / (len - 1);
1008 1009 1010 1011 1012
    ++feature_riter;
  }

  double std = FLAGS_still_obstacle_position_std;
  double speed_threshold = FLAGS_still_obstacle_speed_threshold;
1013 1014 1015
  if (type_ == PerceptionObstacle::PEDESTRIAN ||
      type_ == PerceptionObstacle::BICYCLE) {
    speed_threshold = FLAGS_still_pedestrian_speed_threshold;
1016
    std = FLAGS_still_pedestrian_position_std;
1017
  }
1018 1019 1020 1021 1022
  double delta_ts = feature_history_.front().timestamp() -
                    feature_history_.back().timestamp();
  double speed_sensibility =
      std::sqrt(2 * history_size) * 4 * std / ((history_size + 1) * delta_ts);
  double speed = feature_history_.front().speed();
1023
  if (speed < speed_threshold) {
C
Calvin Miao 已提交
1024
    ADEBUG << "Obstacle [" << id_ << "] has a small speed [" << speed
K
kechxu 已提交
1025
           << "] and is considered stationary.";
1026
    feature_history_.front().set_is_still(true);
1027
  } else if (speed_sensibility < speed_threshold) {
K
kechxu 已提交
1028
    ADEBUG << "Obstacle [" << id_ << "]"
D
Dong Li 已提交
1029
           << "] considered moving [sensibility = " << speed_sensibility << "]";
1030
    feature_history_.front().set_is_still(false);
1031 1032 1033
  } else {
    double distance = std::hypot(avg_drift_x, avg_drift_y);
    double distance_std = std::sqrt(2.0 / len) * std;
1034
    if (distance > 2.0 * distance_std) {
1035
      ADEBUG << "Obstacle [" << id_ << "] is moving.";
1036
      feature_history_.front().set_is_still(false);
1037
    } else {
C
Calvin Miao 已提交
1038
      ADEBUG << "Obstacle [" << id_ << "] is stationary.";
1039
      feature_history_.front().set_is_still(true);
1040 1041
    }
  }
1042 1043
}

1044 1045 1046 1047 1048 1049 1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062 1063 1064 1065 1066
void Obstacle::SetMotionStatusBySpeed() {
  int history_size = static_cast<int>(feature_history_.size());
  if (history_size < 2) {
    ADEBUG << "Obstacle [" << id_ << "] has no history and "
           << "is considered moving.";
    if (history_size > 0) {
      feature_history_.front().set_is_still(false);
    }
    return;
  }

  double speed_threshold = FLAGS_still_obstacle_speed_threshold;
  double speed = feature_history_.front().speed();

  if (FLAGS_use_navigation_mode) {
    if (speed < speed_threshold) {
      feature_history_.front().set_is_still(true);
    } else {
      feature_history_.front().set_is_still(false);
    }
  }
}

C
Calvin Miao 已提交
1067 1068
void Obstacle::InsertFeatureToHistory(const Feature& feature) {
  feature_history_.emplace_front(feature);
1069
  ADEBUG << "Obstacle [" << id_ << "] inserted a frame into the history.";
1070 1071
}

K
kechxu 已提交
1072 1073 1074 1075
void Obstacle::Trim() {
  if (feature_history_.size() < 2) {
    return;
  }
K
kechxu 已提交
1076
  int count = 0;
1077
  const double latest_ts = feature_history_.front().timestamp();
K
kechxu 已提交
1078
  while (!feature_history_.empty() &&
1079 1080
         latest_ts - feature_history_.back().timestamp() >=
             FLAGS_max_history_time) {
K
kechxu 已提交
1081
    feature_history_.pop_back();
K
kechxu 已提交
1082 1083 1084
    ++count;
  }
  if (count > 0) {
D
Dong Li 已提交
1085 1086
    ADEBUG << "Obstacle [" << id_ << "] trimmed " << count
           << " historical features";
K
kechxu 已提交
1087 1088 1089
  }
}

C
Calvin Miao 已提交
1090 1091 1092 1093 1094 1095
void Obstacle::SetRNNStates(const std::vector<Eigen::MatrixXf>& rnn_states) {
  rnn_states_ = rnn_states;
}

void Obstacle::GetRNNStates(std::vector<Eigen::MatrixXf>* rnn_states) {
  rnn_states->clear();
C
Calvin Miao 已提交
1096
  rnn_states->insert(rnn_states->end(), rnn_states_.begin(), rnn_states_.end());
C
Calvin Miao 已提交
1097 1098 1099 1100 1101 1102 1103 1104 1105 1106 1107 1108 1109 1110
}

void Obstacle::InitRNNStates() {
  if (network::RnnModel::instance()->IsOk()) {
    network::RnnModel::instance()->ResetState();
    network::RnnModel::instance()->State(&rnn_states_);
    rnn_enabled_ = true;
    ADEBUG << "Success to initialize rnn model.";
  } else {
    AWARN << "Fail to initialize rnn model.";
    rnn_enabled_ = false;
  }
}

C
Calvin Miao 已提交
1111
bool Obstacle::RNNEnabled() const { return rnn_enabled_; }
C
Calvin Miao 已提交
1112

K
kechxu 已提交
1113 1114
}  // namespace prediction
}  // namespace apollo