trajectory_cost.cc 4.9 KB
Newer Older
Y
Yifei Jiang 已提交
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20
/******************************************************************************
 * 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.
 *****************************************************************************/

/**
 * @file trjactory_cost.h
 **/

D
Dong Li 已提交
21
#include "modules/planning/tasks/dp_poly_path/trajectory_cost.h"
D
Dong Li 已提交
22

J
jiangyifei 已提交
23
#include <algorithm>
Y
Yifei Jiang 已提交
24 25
#include <cmath>

26
#include "modules/common/math/vec2d.h"
27
#include "modules/common/proto/pnc_point.pb.h"
Z
Zhang Liangliang 已提交
28
#include "modules/planning/common/planning_gflags.h"
Y
Yifei Jiang 已提交
29 30 31 32

namespace apollo {
namespace planning {

A
Aaron Xiao 已提交
33 34 35
using apollo::common::math::Box2d;
using apollo::common::math::Vec2d;
using apollo::common::TrajectoryPoint;
Z
zhuweicheng 已提交
36

C
charlie 已提交
37 38 39 40 41 42 43 44 45 46
TrajectoryCost::TrajectoryCost(
    const DpPolyPathConfig &config,
    const ReferenceLine &reference_line,
    const std::vector<const PathObstacle*>& obstacles,
    const common::VehicleParam &vehicle_param,
    const SpeedData &heuristic_speed_data) :
    config_(config),
    reference_line_(&reference_line),
    vehicle_param_(vehicle_param),
    heuristic_speed_data_(heuristic_speed_data) {
Y
Yifei Jiang 已提交
47
  const double total_time =
48
      std::min(heuristic_speed_data_.TotalTime(), FLAGS_prediction_total_time);
Y
Yajia Zhang 已提交
49 50

  num_of_time_stamps_ = static_cast<uint32_t>(
D
Dong Li 已提交
51
      std::floor(total_time / config.eval_time_interval()));
C
charlie 已提交
52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70

  for (const auto ptr_path_obstacle : obstacles) {
    if (ptr_path_obstacle->IsIgnore()) {
      continue;
    }
    const auto ptr_obstacle = ptr_path_obstacle->obstacle();
    if (ptr_obstacle->PerceptionId() < 0) {
      //Virtual obsatcle
      continue;
    }
    std::vector<Box2d> box_by_time;
    for (uint32_t t = 0; t <= num_of_time_stamps_; ++t) {
      TrajectoryPoint trajectory_point =
        ptr_obstacle->GetPointAtTime(t * config.eval_time_interval());
      Box2d obs_box = ptr_obstacle->GetBoundingBox(trajectory_point);
      box_by_time.push_back(obs_box);
    }
    obstacle_boxes_.push_back(box_by_time);
  }
Y
Yifei Jiang 已提交
71 72
}

A
Aaron Xiao 已提交
73
double TrajectoryCost::Calculate(const QuinticPolynomialCurve1d &curve,
74 75
                                 const double start_s,
                                 const double end_s) const {
Y
Yifei Jiang 已提交
76
  double total_cost = 0.0;
D
Dong Li 已提交
77
  // path_cost
Z
zhuweicheng 已提交
78 79
  double path_s = 0.0;
  while (path_s < (end_s - start_s)) {
80
    double l = std::fabs(curve.Evaluate(0, path_s));
Z
zhuweicheng 已提交
81
    total_cost += l;
Y
Yifei Jiang 已提交
82

83
    double dl = std::fabs(curve.Evaluate(1, path_s));
Z
zhuweicheng 已提交
84
    total_cost += dl;
C
charlie 已提交
85 86

    path_s += config_.path_resolution();
D
Dong Li 已提交
87
  }
C
charlie 已提交
88
  
D
Dong Li 已提交
89
  // obstacle cost
C
charlie 已提交
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
  uint32_t start_index = 0;
  bool is_found_start_index = false;
  uint32_t end_index = 0;
  uint32_t index = 0;
  double time_stamp = 0.0;
  while (end_index != 0) {
    common::SpeedPoint speed_point;
    heuristic_speed_data_.EvaluateByTime(time_stamp, &speed_point);
    if (speed_point.s() >= start_s && !is_found_start_index) {
      start_index = index;
      is_found_start_index = true;
    }
    if (speed_point.s() > end_s) {
      end_index = index;
    }
    time_stamp += config_.eval_time_interval();
    ++index;
  }

  for (; start_index < end_index; ++start_index) {
    common::SpeedPoint speed_point;
    heuristic_speed_data_.EvaluateByTime(
                  start_index * config_.eval_time_interval(), &speed_point);
    double s = speed_point.s() - start_s;
    double l = curve.Evaluate(0, s);
    double dl = curve.Evaluate(1, s);
    Vec2d ego_xy_point;
    common::SLPoint sl;
    sl.set_s(speed_point.s());
    sl.set_l(l);
    reference_line_->SLToXY(sl, &ego_xy_point);
    ReferencePoint reference_point = 
          reference_line_->GetReferencePoint(speed_point.s());

    double one_minus_kappa_r_d = 1 - reference_point.kappa() * l;
    double delta_theta = std::atan2(dl, one_minus_kappa_r_d);
Z
Zhang Liangliang 已提交
126
    double theta = common::math::NormalizeAngle(
C
charlie 已提交
127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143
                                      delta_theta + reference_point.heading());
    Box2d ego_box = {ego_xy_point, theta, 
                     vehicle_param_.length(), vehicle_param_.width()};
    for (const auto &obstacle_trajectory : obstacle_boxes_) {
      auto &obstacle_box = obstacle_trajectory[start_index];
      double distance = obstacle_box.DistanceTo(ego_box);
      if (distance > 10.0) {
        continue;
      } else if (distance <= 0.2) {
        total_cost += 1e3;
      } else if (distance <= 2.0) {
        total_cost += (5.0 - distance) * ((5.0 - distance)) * 10;
      } else {
        total_cost += 10 - distance;
      }
    }
  }
Y
Yifei Jiang 已提交
144 145 146 147
  return total_cost;
}

}  // namespace planning
Z
Zhang Liangliang 已提交
148
}  // namespace apollo