提交 be6d9426 编写于 作者: P panjiacheng 提交者: Xiangquan Xiao

Prediction: put global constants into a single class.

上级 05c5b3f4
......@@ -89,6 +89,7 @@ cc_library(
hdrs = ["road_graph.h"],
deps = [
":prediction_map",
"//modules/prediction/common:prediction_constants",
"//modules/prediction/common:prediction_gflags",
"//modules/prediction/proto:lane_graph_proto",
],
......@@ -243,4 +244,9 @@ cc_library(
],
)
cc_library(
name = "prediction_constants",
hdrs = ["prediction_constants.h"],
)
cpplint()
/******************************************************************************
* Copyright 2019 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
* @brief Holds all global constants for the prediction module.
*/
#pragma once
namespace apollo {
namespace prediction {
class PredictionConstants {
public:
static const int kOnlineMode = 0;
static const int kDumpFeatureProto = 1;
static const int kDumpDataForLearning = 2;
static const int kDumpPredictionResult = 3;
static const int kDumpFrameEnv = 4;
static const int kDumpDataForTuning = 5;
};
} // namespace prediction
} // namespace apollo
......@@ -19,6 +19,7 @@
#include <algorithm>
#include <utility>
#include "modules/prediction/common/prediction_constants.h"
#include "modules/prediction/common/prediction_gflags.h"
#include "modules/prediction/common/prediction_system_gflags.h"
......@@ -188,8 +189,10 @@ void RoadGraph::ComputeLaneSequence(
// Run recursion function to perform DFS.
for (const auto& successor_lane : successor_lanes) {
bool consider_divide_further = false;
if (FLAGS_prediction_offline_mode == 1 ||
FLAGS_prediction_offline_mode == 2) {
if (FLAGS_prediction_offline_mode ==
PredictionConstants::kDumpFeatureProto ||
FLAGS_prediction_offline_mode ==
PredictionConstants::kDumpDataForLearning) {
consider_divide_further = true;
}
ComputeLaneSequence(successor_accumulated_s, 0.0,
......
......@@ -9,6 +9,7 @@ cc_library(
deps = [
"//modules/prediction/common:environment_features",
"//modules/prediction/common:feature_output",
"//modules/prediction/common:prediction_constants",
"//modules/prediction/container",
"//modules/prediction/container/obstacles:obstacle",
],
......
......@@ -21,6 +21,7 @@
#include "modules/prediction/common/feature_output.h"
#include "modules/prediction/common/junction_analyzer.h"
#include "modules/prediction/common/prediction_constants.h"
#include "modules/prediction/common/prediction_gflags.h"
#include "modules/prediction/common/prediction_system_gflags.h"
#include "modules/prediction/container/obstacles/obstacle_clusters.h"
......@@ -30,6 +31,7 @@ namespace prediction {
using apollo::perception::PerceptionObstacle;
using apollo::perception::PerceptionObstacles;
using apollo::prediction::PredictionConstants;
ObstaclesContainer::ObstaclesContainer()
: ptr_obstacles_(FLAGS_max_num_obstacles),
......@@ -344,8 +346,10 @@ void ObstaclesContainer::BuildLaneGraph() {
AERROR << "Null obstacle found.";
continue;
}
if (FLAGS_prediction_offline_mode != 1 &&
FLAGS_prediction_offline_mode != 2) {
if (FLAGS_prediction_offline_mode !=
PredictionConstants::kDumpFeatureProto &&
FLAGS_prediction_offline_mode !=
PredictionConstants::kDumpDataForLearning) {
ADEBUG << "Building Lane Graph.";
obstacle_ptr->BuildLaneGraph();
} else {
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册