提交 9bcd3ccd 编写于 作者: A Aaron Xiao 提交者: Jiangtao Hu

Planning: simple code clean.

上级 2eb76b17
......@@ -122,12 +122,10 @@ bool DPRoadGraph::GenerateMinCostPath(
for (std::size_t level = 1; level < path_waypoints.size(); ++level) {
const auto &prev_dp_nodes = graph_nodes[level - 1];
const auto &level_points = path_waypoints[level];
for (std::size_t i = 0; i < level_points.size(); ++i) {
const auto &cur_point = level_points[i];
for (const auto &cur_point : level_points) {
graph_nodes[level].emplace_back(cur_point, nullptr);
auto &cur_node = graph_nodes[level].back();
for (std::size_t j = 0; j < prev_dp_nodes.size(); ++j) {
const auto &prev_dp_node = prev_dp_nodes[j];
for (const auto &prev_dp_node : prev_dp_nodes) {
const auto &prev_sl_point = prev_dp_node.sl_point;
QuinticPolynomialCurve1d curve(prev_sl_point.l(), 0.0, 0.0,
cur_point.l(), 0.0, 0.0,
......@@ -142,9 +140,7 @@ bool DPRoadGraph::GenerateMinCostPath(
// find best path
DPRoadGraphNode fake_head;
const auto &last_dp_nodes = graph_nodes.back();
for (std::size_t i = 0; i < last_dp_nodes.size(); ++i) {
const auto &cur_dp_node = last_dp_nodes[i];
for (const auto &cur_dp_node : graph_nodes.back()) {
fake_head.UpdateCost(&cur_dp_node, cur_dp_node.min_cost_curve,
cur_dp_node.min_cost);
}
......
......@@ -30,9 +30,9 @@
namespace apollo {
namespace planning {
using Box2d = ::apollo::common::math::Box2d;
using Vec2d = ::apollo::common::math::Vec2d;
using TrajectoryPoint = ::apollo::common::TrajectoryPoint;
using apollo::common::math::Box2d;
using apollo::common::math::Vec2d;
using apollo::common::TrajectoryPoint;
TrajectoryCost::TrajectoryCost(const DpPolyPathConfig &config,
const ReferenceLine &reference_line,
......
......@@ -118,12 +118,11 @@ double DpStCost::GetAccelCostByTwoPoints(const double pre_speed,
double DpStCost::JerkCost(const double jerk) const {
double jerk_sq = jerk * jerk;
double cost = 0.0;
if (Double::Compare(jerk, 0.0) > 0) {
const auto diff = Double::Compare(jerk, 0.0);
if (diff > 0) {
cost = dp_st_speed_config_.positive_jerk_coeff() * jerk_sq * unit_t_;
} else if (Double::Compare(jerk, 0.0) < 0) {
} else if (diff < 0) {
cost = dp_st_speed_config_.negative_jerk_coeff() * jerk_sq * unit_t_;
} else {
cost = 0.0;
}
return cost;
}
......
......@@ -35,12 +35,12 @@
namespace apollo {
namespace planning {
using ErrorCode = apollo::common::ErrorCode;
using SpeedPoint = apollo::common::SpeedPoint;
using Status = apollo::common::Status;
using Vec2d = apollo::common::math::Vec2d;
using VehicleConfigHelper = apollo::common::VehicleConfigHelper;
using VehicleParam = apollo::common::VehicleParam;
using apollo::common::ErrorCode;
using apollo::common::SpeedPoint;
using apollo::common::Status;
using apollo::common::math::Vec2d;
using apollo::common::VehicleConfigHelper;
using apollo::common::VehicleParam;
namespace {
......@@ -150,14 +150,14 @@ void DpStGraph::CalculatePointwiseCost(
}
for (uint32_t i = 0; i < cost_table_.size(); ++i) {
for (uint32_t j = 0; j < cost_table_[i].size(); ++j) {
double ref_cost = dp_st_cost_.GetReferenceCost(cost_table_[i][j].point(),
for (auto& st_graph_point : cost_table_[i]) {
double ref_cost = dp_st_cost_.GetReferenceCost(st_graph_point.point(),
reference_points[i]);
double obs_cost =
dp_st_cost_.GetObstacleCost(cost_table_[i][j].point(), boundaries);
cost_table_[i][j].SetReferenceCost(ref_cost);
cost_table_[i][j].SetObstacleCost(obs_cost);
cost_table_[i][j].SetTotalCost(std::numeric_limits<double>::infinity());
dp_st_cost_.GetObstacleCost(st_graph_point.point(), boundaries);
st_graph_point.SetReferenceCost(ref_cost);
st_graph_point.SetObstacleCost(obs_cost);
st_graph_point.SetTotalCost(std::numeric_limits<double>::infinity());
}
}
}
......@@ -165,11 +165,10 @@ void DpStGraph::CalculatePointwiseCost(
Status DpStGraph::CalculateTotalCost() {
// s corresponding to row
// time corresponding to col
uint32_t c = 0;
uint32_t next_highest_row = 0;
uint32_t next_lowest_row = 0;
while (c < cost_table_.size()) {
for (size_t c = 0; c < cost_table_.size(); ++c) {
uint32_t highest_row = 0;
uint32_t lowest_row = cost_table_.back().size() - 1;
for (uint32_t r = next_lowest_row; r <= next_highest_row; ++r) {
......@@ -183,7 +182,6 @@ Status DpStGraph::CalculateTotalCost() {
lowest_row = std::min(lowest_row, l_r);
}
}
++c;
next_highest_row = highest_row;
next_lowest_row = std::max(next_lowest_row, lowest_row);
}
......@@ -216,8 +214,7 @@ void DpStGraph::GetRowRange(const uint32_t curr_row, const uint32_t curr_col,
const double delta_s_lower_bound = std::fmax(
0.0, v0 * unit_t_ + vehicle_param_.max_deceleration() * speed_coeff);
*next_lowest_row =
*next_lowest_row + static_cast<int32_t>(delta_s_lower_bound / unit_s_);
*next_lowest_row += static_cast<int32_t>(delta_s_lower_bound / unit_s_);
if (*next_lowest_row >= cost_table_.back().size()) {
*next_lowest_row = cost_table_.back().size() - 1;
}
......@@ -342,12 +339,8 @@ bool DpStGraph::CalculateFeasibleAccelRange(const double r_pre,
Status DpStGraph::RetrieveSpeedProfile(SpeedData* const speed_data) const {
double min_cost = std::numeric_limits<double>::infinity();
uint32_t n = cost_table_.back().size();
uint32_t m = cost_table_.size();
const StGraphPoint* best_end_point = nullptr;
for (uint32_t i = 0; i < n; ++i) {
const StGraphPoint& cur_point = cost_table_.back()[i];
for (const StGraphPoint& cur_point : cost_table_.back()) {
if (!std::isinf(cur_point.total_cost()) &&
cur_point.total_cost() < min_cost) {
best_end_point = &cur_point;
......@@ -355,8 +348,8 @@ Status DpStGraph::RetrieveSpeedProfile(SpeedData* const speed_data) const {
}
}
for (uint32_t i = 0; i < m; ++i) {
const StGraphPoint& cur_point = cost_table_[i].back();
for (const auto& row : cost_table_) {
const StGraphPoint& cur_point = row.back();
if (!std::isinf(cur_point.total_cost()) &&
cur_point.total_cost() < min_cost) {
best_end_point = &cur_point;
......
......@@ -40,7 +40,7 @@ using apollo::common::Status;
using apollo::common::VehicleConfigHelper;
using apollo::common::adapter::AdapterManager;
using apollo::localization::LocalizationEstimate;
using ::apollo::planning_internal::STGraphDebug;
using apollo::planning_internal::STGraphDebug;
DpStSpeedOptimizer::DpStSpeedOptimizer()
: SpeedOptimizer("DpStSpeedOptimizer") {}
......
......@@ -36,9 +36,7 @@ namespace planning {
using apollo::common::ErrorCode;
using apollo::common::Status;
namespace {
const double kTimeSampleInterval = 0.1;
}
PathDecider::PathDecider() : Task("PathDecider") {}
......@@ -108,8 +106,7 @@ bool PathDecider::MakeStaticObstacleDecision(
const auto &sl_boundary = path_obstacle->perception_sl_boundary();
bool has_stop = false;
for (std::size_t j = 0; j < adc_sl_points.size(); ++j) {
const auto &adc_sl = adc_sl_points[j];
for (const auto &adc_sl : adc_sl_points) {
if (adc_sl.s() + adc_max_edge_to_center_dist +
FLAGS_static_decision_ignore_s_range <
sl_boundary.start_s() ||
......
......@@ -85,13 +85,11 @@ bool QpFrenetFrame::Init(const uint32_t num_points,
const auto inf = std::numeric_limits<double>::infinity();
const double resolution = (end_s_ - start_s_) / num_points;
double s = start_s_;
while (s <= end_s_) {
for (double s = start_s_; s <= end_s_; s += resolution) {
evaluated_knots_.push_back(s);
hdmap_bound_.emplace_back(-inf, inf);
static_obstacle_bound_.emplace_back(-inf, inf);
dynamic_obstacle_bound_.emplace_back(-inf, inf);
s += resolution;
}
// initialize calculation here
......@@ -141,8 +139,8 @@ bool QpFrenetFrame::GetDynamicObstacleBound(
}
bool QpFrenetFrame::CalculateDiscretizedVehicleLocation() {
double relative_time = 0.0;
while (relative_time < speed_data_.TotalTime()) {
for (double relative_time = 0.0; relative_time < speed_data_.TotalTime();
relative_time += time_resolution_) {
SpeedPoint veh_point;
if (!speed_data_.EvaluateByTime(relative_time, &veh_point)) {
AERROR << "Fail to get speed point at relative time " << relative_time;
......@@ -150,7 +148,6 @@ bool QpFrenetFrame::CalculateDiscretizedVehicleLocation() {
}
veh_point.set_t(relative_time);
discretized_vehicle_location_.push_back(std::move(veh_point));
relative_time += time_resolution_;
}
return true;
}
......
......@@ -33,7 +33,7 @@ namespace planning {
using apollo::common::ErrorCode;
using apollo::common::Status;
using apollo::common::VehicleParam;
using ::apollo::planning_internal::STGraphDebug;
using apollo::planning_internal::STGraphDebug;
QpSplineStGraph::QpSplineStGraph(
const QpSplineStSpeedConfig& qp_spline_st_speed_config,
......@@ -71,8 +71,7 @@ void QpSplineStGraph::Init() {
Status QpSplineStGraph::Search(const StGraphData& st_graph_data,
const PathData& path_data,
SpeedData* const speed_data,
STGraphDebug* st_graph_debug
) {
STGraphDebug* st_graph_debug) {
init_point_ = st_graph_data.init_point();
if (st_graph_data.path_data_length() <
qp_spline_st_speed_config_.total_path_length()) {
......
......@@ -39,7 +39,6 @@
namespace apollo {
namespace planning {
using ::apollo::planning_internal::STGraphDebug;
class QpSplineStGraph {
public:
......@@ -48,7 +47,7 @@ class QpSplineStGraph {
common::Status Search(const StGraphData& st_graph_data,
const PathData& path_data, SpeedData* const speed_data,
STGraphDebug* st_graph_debug);
planning_internal::STGraphDebug* st_graph_debug);
private:
void Init();
......@@ -57,7 +56,7 @@ class QpSplineStGraph {
common::Status ApplyConstraint(
const common::TrajectoryPoint& init_point, const SpeedLimit& speed_limit,
const std::vector<StBoundary>& boundaries,
STGraphDebug* st_graph_debug);
planning_internal::STGraphDebug* st_graph_debug);
// apply objective function
common::Status ApplyKernel(const std::vector<StBoundary>& boundaries,
......
......@@ -35,10 +35,10 @@
namespace apollo {
namespace planning {
using Status = apollo::common::Status;
using ErrorCode = apollo::common::ErrorCode;
using TrajectoryPoint = apollo::common::TrajectoryPoint;
using ::apollo::planning_internal::STGraphDebug;
using apollo::common::ErrorCode;
using apollo::common::Status;
using apollo::common::TrajectoryPoint;
using apollo::planning_internal::STGraphDebug;
QpSplineStSpeedOptimizer::QpSplineStSpeedOptimizer()
: SpeedOptimizer("QpSplineStSpeedOptimizer") {}
......
......@@ -49,9 +49,6 @@ class QpSplineStSpeedOptimizer : public SpeedOptimizer {
PathDecision* const path_decision,
SpeedData* const speed_data) override;
void GenerateStopProfile(const double init_speed,
SpeedData* const speed_data) const;
QpSplineStSpeedConfig qp_spline_st_speed_config_;
StBoundaryConfig st_boundary_config_;
};
......
......@@ -25,7 +25,8 @@
namespace apollo {
namespace planning {
using ::apollo::planning_internal::STGraphDebug;
using apollo::planning_internal::StGraphBoundaryDebug;
using apollo::planning_internal::STGraphDebug;
SpeedOptimizer::SpeedOptimizer(const std::string& name) : Task(name) {}
......@@ -93,29 +94,21 @@ void SpeedOptimizer::RecordSTGraphDebug(
boundary_debug->set_name(boundary.id());
switch (boundary.boundary_type()) {
case StBoundary::BoundaryType::FOLLOW:
boundary_debug->set_type(
::apollo::planning_internal::StGraphBoundaryDebug::
ST_BOUNDARY_TYPE_FOLLOW);
boundary_debug->set_type(StGraphBoundaryDebug::ST_BOUNDARY_TYPE_FOLLOW);
break;
case StBoundary::BoundaryType::OVERTAKE:
boundary_debug->set_type(
::apollo::planning_internal::StGraphBoundaryDebug::
ST_BOUNDARY_TYPE_OVERTAKE);
StGraphBoundaryDebug::ST_BOUNDARY_TYPE_OVERTAKE);
break;
case StBoundary::BoundaryType::STOP:
boundary_debug->set_type(
::apollo::planning_internal::StGraphBoundaryDebug::
ST_BOUNDARY_TYPE_STOP);
boundary_debug->set_type(StGraphBoundaryDebug::ST_BOUNDARY_TYPE_STOP);
break;
case StBoundary::BoundaryType::UNKNOWN:
boundary_debug->set_type(
::apollo::planning_internal::StGraphBoundaryDebug::
ST_BOUNDARY_TYPE_UNKNOWN);
StGraphBoundaryDebug::ST_BOUNDARY_TYPE_UNKNOWN);
break;
case StBoundary::BoundaryType::YIELD:
boundary_debug->set_type(
::apollo::planning_internal::StGraphBoundaryDebug::
ST_BOUNDARY_TYPE_YIELD);
boundary_debug->set_type(StGraphBoundaryDebug::ST_BOUNDARY_TYPE_YIELD);
break;
}
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册