提交 f6ce2aab 编写于 作者: J jmtao 提交者: Liangliang Zhang

planning: update CheckPlanningConfig

上级 349d9239
......@@ -59,7 +59,11 @@ Status NaviPlanning::Init() {
CHECK(apollo::common::util::GetProtoFromFile(FLAGS_planning_config_file,
&config_))
<< "failed to load planning config file " << FLAGS_planning_config_file;
CheckPlanningConfig();
if (!CheckPlanningConfig()) {
return Status(ErrorCode::PLANNING_ERROR,
"planning config error: " + config_.DebugString());
}
planner_dispatcher_->Init();
......@@ -641,5 +645,14 @@ NaviPlanning::VehicleConfig NaviPlanning::ComputeVehicleConfigFromLocalization(
return vehicle_config;
}
bool NaviPlanning::CheckPlanningConfig() {
if (!config_.has_planner_navi_config()) {
return false;
}
// TODO(All): check other config params
return true;
}
} // namespace planning
} // namespace apollo
......@@ -89,6 +89,9 @@ class NaviPlanning : public PlanningBase {
const common::TrajectoryPoint& planning_start_point,
const double start_time,
const common::VehicleState& vehicle_state);
bool CheckPlanningConfig();
/**
* @brief receiving planning pad message
*/
......
......@@ -53,7 +53,11 @@ Status OpenSpacePlanning::Init() {
CHECK(apollo::common::util::GetProtoFromFile(FLAGS_planning_config_file,
&config_))
<< "failed to load planning config file " << FLAGS_planning_config_file;
CheckPlanningConfig();
if (!CheckPlanningConfig()) {
return Status(ErrorCode::PLANNING_ERROR,
"planning config error: " + config_.DebugString());
}
// clear planning status
GetPlanningStatus()->Clear();
......@@ -194,5 +198,14 @@ common::Status OpenSpacePlanning::InitFrame(
return Status::OK();
}
bool OpenSpacePlanning::CheckPlanningConfig() {
if (!config_.has_planner_open_space_config()) {
return false;
}
// TODO(All): check other config params
return true;
}
} // namespace planning
} // namespace apollo
......@@ -81,6 +81,9 @@ class OpenSpacePlanning : public PlanningBase {
const common::TrajectoryPoint& planning_start_point,
const double start_time,
const common::VehicleState& vehicle_state);
bool CheckPlanningConfig();
private:
std::unique_ptr<FrameOpenSpace> frame_;
};
......
......@@ -51,25 +51,6 @@ using apollo::hdmap::HDMapUtil;
PlanningBase::~PlanningBase() {}
void PlanningBase::CheckPlanningConfig() {
if (config_.has_planner_em_config() &&
config_.planner_em_config().has_scenario_config() &&
config_.planner_em_config().scenario_config()
.has_scenario_lane_follow_config() &&
config_.planner_em_config().scenario_config()
.scenario_lane_follow_config().has_dp_st_speed_config()) {
const auto& dp_st_speed_config = config_.planner_em_config()
.scenario_config().scenario_lane_follow_config().dp_st_speed_config();
CHECK(dp_st_speed_config.has_matrix_dimension_s());
CHECK_GT(dp_st_speed_config.matrix_dimension_s(), 3);
CHECK_LT(dp_st_speed_config.matrix_dimension_s(), 10000);
CHECK(dp_st_speed_config.has_matrix_dimension_t());
CHECK_GT(dp_st_speed_config.matrix_dimension_t(), 3);
CHECK_LT(dp_st_speed_config.matrix_dimension_t(), 10000);
}
// TODO(All): check other config params
}
bool PlanningBase::IsVehicleStateValid(const VehicleState& vehicle_state) {
if (std::isnan(vehicle_state.x()) || std::isnan(vehicle_state.y()) ||
std::isnan(vehicle_state.z()) || std::isnan(vehicle_state.heading()) ||
......
......@@ -81,8 +81,9 @@ class PlanningBase : public apollo::common::ApolloApp {
bool IsVehicleStateValid(const common::VehicleState& vehicle_state);
virtual void SetFallbackTrajectory(ADCTrajectory* cruise_trajectory);
void CheckPlanningConfig();
virtual bool CheckPlanningConfig() = 0;
protected:
double start_time_ = 0.0;
PlanningConfig config_;
TrafficRuleConfigs traffic_rule_configs_;
......
......@@ -36,24 +36,15 @@ message ScenarioLaneFollowConfig {
message ScenarioConfig {
enum ScenarioType {
// LANE_FOLLOW is the default scenario
LANE_FOLLOW = 0;
// change from one lane to an adjacent lane
LANE_FOLLOW = 0; // default scenario
CHANGE_LANE = 1;
// go around an object when it blocks the road.
SIDE_PASS = 2;
// approach to an intersection
APPROACH = 3;
// drive at an intersection with 4-way stop sign
SIDE_PASS = 2; // go around an object when it blocks the road
APPROACH = 3; // approach to an intersection
INTERSECTION_STOP_SIGN_FOUR_WAY = 4;
// drive at an intersection with 1 or 2 way stop sign
INTERSECTION_STOP_SIGN_ONE_OR_TWO_WAY = 5;
// turn left at an intersection with traffic light
INTERSECTION_TRAFFIC_LIGHT_LEFT_TURN = 6;
// turn right at an intersection with traffic light
INTERSECTION_TRAFFIC_LIGHT_RIGHT_TURN = 7;
// go through an intersection with traffic light
INTERSECTION_TRAFFIC_GO_THROUGH = 8;
INTERSECTION_TRAFFIC_LIGHT_GO_THROUGH = 8;
}
optional ScenarioType scenario_type = 1;
......@@ -62,10 +53,16 @@ message ScenarioConfig {
}
};
message PlannerRTKonfig {
}
message PlannerEMConfig {
optional ScenarioConfig scenario_config = 1;
}
message PlannerLatticeonfig {
}
message PlannerNaviConfig {
repeated TaskType task = 1;
optional apollo.planning.NaviPathDeciderConfig navi_path_decider_config = 2;
......@@ -83,8 +80,10 @@ message PlanningConfig {
};
optional PlannerType planner_type = 1 [default = EM];
oneof planner_config {
PlannerEMConfig planner_em_config = 2;
PlannerNaviConfig planner_navi_config = 3;
PlannerOpenSpaceConfig planner_open_space_config = 4;
PlannerRTKonfig planner_rtk_config = 2;
PlannerEMConfig planner_em_config = 3;
PlannerLatticeonfig planner_lattice_config = 4;
PlannerNaviConfig planner_navi_config = 5;
PlannerOpenSpaceConfig planner_open_space_config = 6;
}
}
......@@ -77,7 +77,10 @@ Status StdPlanning::Init() {
CHECK(apollo::common::util::GetProtoFromFile(FLAGS_planning_config_file,
&config_))
<< "failed to load planning config file " << FLAGS_planning_config_file;
CheckPlanningConfig();
if (!CheckPlanningConfig()) {
return Status(ErrorCode::PLANNING_ERROR,
"planning config error: " + config_.DebugString());
}
planner_dispatcher_->Init();
......@@ -460,5 +463,34 @@ void StdPlanning::Stop() {
EgoInfo::instance()->Clear();
}
bool StdPlanning::CheckPlanningConfig() {
if (!config_.has_planner_em_config()) {
return false;
}
if (!config_.planner_em_config().has_scenario_config()) {
return false;
}
if (!config_.planner_em_config().scenario_config()
.has_scenario_lane_follow_config()) {
return false;
}
if (!config_.planner_em_config().scenario_config()
.scenario_lane_follow_config().has_dp_st_speed_config()) {
return false;
}
const auto& dp_st_speed_config = config_.planner_em_config()
.scenario_config().scenario_lane_follow_config().dp_st_speed_config();
CHECK(dp_st_speed_config.has_matrix_dimension_s());
CHECK_GT(dp_st_speed_config.matrix_dimension_s(), 3);
CHECK_LT(dp_st_speed_config.matrix_dimension_s(), 10000);
CHECK(dp_st_speed_config.has_matrix_dimension_t());
CHECK_GT(dp_st_speed_config.matrix_dimension_t(), 3);
CHECK_LT(dp_st_speed_config.matrix_dimension_t(), 10000);
// TODO(All): check other config params
return true;
}
} // namespace planning
} // namespace apollo
......@@ -86,13 +86,12 @@ class StdPlanning : public PlanningBase {
const common::TrajectoryPoint& planning_start_point,
const double start_time,
const common::VehicleState& vehicle_state);
routing::RoutingResponse last_routing_;
void ExportReferenceLineDebug(planning_internal::Debug* debug);
bool CheckPlanningConfig();
private:
routing::RoutingResponse last_routing_;
std::unique_ptr<Frame> frame_;
std::unique_ptr<ReferenceLineProvider> reference_line_provider_;
};
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册