提交 456f0fba 编写于 作者: L Liangliang Zhang 提交者: Jiangtao Hu

Planning: make planning compilable.

上级 6d7fc589
......@@ -107,9 +107,8 @@ function generate_build_targets() {
//modules/control/proto/...
//modules/localization/proto/...
//modules/perception/proto/...
//modules/planning/common/...
//modules/planning:planning_component_lib
//modules/planning/proto/..."
# //modules/planning:planning_component_lib
# //modules/drivers/radar/conti_radar/...
# //modules/drivers/gnss/...
# //modules/monitor/...
......
......@@ -47,9 +47,9 @@ TEST(EgoInfoTest, EgoInfoSimpleTest) {
common::VehicleState vehicle_state;
ReferenceLineProvider reference_line_provider;
PlanningData pd;
Frame frame(sequence_num, pd, planning_start_point, start_time, vehicle_state,
&reference_line_provider);
PlanningData dummy_planning_data;
Frame frame(sequence_num, dummy_planning_data, planning_start_point,
start_time, vehicle_state, &reference_line_provider);
ego_info->CalculateFrontObstacleClearDistance(frame.obstacles());
}
......
......@@ -120,6 +120,8 @@ class Frame {
void UpdateReferenceLinePriority(
const std::map<std::string, uint32_t> &id_to_priority);
const PlanningData &planning_data() const { return planning_data_; }
private:
bool CreateReferenceLineInfo();
......
......@@ -11,7 +11,7 @@ cc_library(
"//modules/common/proto:pnc_point_proto",
"//modules/common/status",
"//modules/planning/common:frame",
"//modules/planning/common:frame_open_space",
#"//modules/planning/common:frame_open_space",
"//modules/planning/common:reference_line_info",
"//modules/planning/proto:planning_proto",
"//modules/planning/scenarios:scenario_lib",
......@@ -22,12 +22,12 @@ cc_library(
cc_library(
name = "planner_dispatcher",
srcs = [
"navi_planner_dispatcher.cc",
#"navi_planner_dispatcher.cc",
"planner_dispatcher.cc",
"std_planner_dispatcher.cc",
],
hdrs = [
"navi_planner_dispatcher.h",
#"navi_planner_dispatcher.h",
"planner_dispatcher.h",
"std_planner_dispatcher.h",
],
......@@ -35,9 +35,9 @@ cc_library(
"//modules/common/status",
"//modules/common/util",
"//modules/planning/planner/em:em_planner",
"//modules/planning/planner/navi:navi_planner",
"//modules/planning/planner/lattice:lattice_planner",
"//modules/planning/planner/open_space:open_space_planner",
#"//modules/planning/planner/navi:navi_planner",
#"//modules/planning/planner/lattice:lattice_planner",
#"//modules/planning/planner/open_space:open_space_planner",
"//modules/planning/planner/rtk:rtk_planner",
"//modules/planning/proto:planning_proto",
],
......@@ -55,16 +55,16 @@ cc_test(
],
)
cc_test(
name = "navi_planner_dispatcher_test",
size = "small",
srcs = [
"navi_planner_dispatcher_test.cc",
],
deps = [
":planner_dispatcher",
"@gtest//:main",
],
)
# cc_test(
# name = "navi_planner_dispatcher_test",
# size = "small",
# srcs = [
# "navi_planner_dispatcher_test.cc",
# ],
# deps = [
# ":planner_dispatcher",
# "@gtest//:main",
# ],
# )
cpplint()
......@@ -19,9 +19,9 @@
#include "modules/planning/proto/planning_config.pb.h"
#include "modules/planning/planner/em/em_planner.h"
#include "modules/planning/planner/lattice/lattice_planner.h"
#include "modules/planning/planner/navi/navi_planner.h"
#include "modules/planning/planner/open_space/open_space_planner.h"
//#include "modules/planning/planner/lattice/lattice_planner.h"
//#include "modules/planning/planner/navi/navi_planner.h"
//#include "modules/planning/planner/open_space/open_space_planner.h"
#include "modules/planning/planner/rtk/rtk_replay_planner.h"
namespace apollo {
......@@ -32,10 +32,10 @@ void PlannerDispatcher::RegisterPlanners() {
RTK, []() -> Planner* { return new RTKReplayPlanner(); });
planner_factory_.Register(ONROAD,
[]() -> Planner* { return new EMPlanner(); });
planner_factory_.Register(
OPENSPACE, []() -> Planner* { return new OpenSpacePlanner(); });
planner_factory_.Register(NAVI,
[]() -> Planner* { return new NaviPlanner(); });
// planner_factory_.Register(
// OPENSPACE, []() -> Planner* { return new OpenSpacePlanner(); });
// planner_factory_.Register(NAVI,
// []() -> Planner* { return new NaviPlanner(); });
}
} // namespace planning
......
......@@ -24,7 +24,6 @@
#include <limits>
#include <utility>
#include "modules/common/adapters/adapter_manager.h"
#include "modules/common/log.h"
#include "modules/common/math/math_utils.h"
#include "modules/common/time/time.h"
......@@ -54,7 +53,6 @@ using common::SLPoint;
using common::SpeedPoint;
using common::Status;
using common::TrajectoryPoint;
using common::adapter::AdapterManager;
using common::math::Vec2d;
using common::time::Clock;
......
......@@ -26,7 +26,6 @@
#include "modules/routing/proto/routing.pb.h"
#include "modules/common/adapters/adapter_manager.h"
#include "modules/common/math/quaternion.h"
#include "modules/common/time/time.h"
#include "modules/common/vehicle_state/vehicle_state_provider.h"
......@@ -35,7 +34,7 @@
#include "modules/planning/common/planning_context.h"
#include "modules/planning/common/planning_gflags.h"
#include "modules/planning/common/trajectory/trajectory_stitcher.h"
#include "modules/planning/planner/navi/navi_planner.h"
//#include "modules/planning/planner/navi/navi_planner.h"
#include "modules/planning/planner/rtk/rtk_replay_planner.h"
#include "modules/planning/reference_line/reference_line_provider.h"
#include "modules/planning/toolkits/deciders/traffic_decider.h"
......@@ -48,7 +47,6 @@ using apollo::common::Status;
using apollo::common::TrajectoryPoint;
using apollo::common::VehicleState;
using apollo::common::VehicleStateProvider;
using apollo::common::adapter::AdapterManager;
using apollo::common::time::Clock;
using apollo::hdmap::HDMapUtil;
using apollo::routing::RoutingResponse;
......@@ -138,8 +136,9 @@ Status StdPlanning::InitFrame(const uint32_t sequence_num,
const TrajectoryPoint& planning_start_point,
const double start_time,
const VehicleState& vehicle_state) {
frame_.reset(new Frame(sequence_num, planning_start_point, start_time,
vehicle_state, reference_line_provider_.get()));
frame_.reset(new Frame(sequence_num, planning_data_, planning_start_point,
start_time, vehicle_state,
reference_line_provider_.get()));
auto status = frame_->Init();
if (!status.ok()) {
AERROR << "failed to init frame:" << status.ToString();
......
......@@ -22,7 +22,6 @@
#include "modules/planning/toolkits/deciders/destination.h"
#include "modules/common/adapters/adapter_manager.h"
#include "modules/common/time/time.h"
#include "modules/map/proto/map_lane.pb.h"
#include "modules/planning/common/planning_context.h"
......@@ -32,7 +31,6 @@ namespace apollo {
namespace planning {
using apollo::common::Status;
using apollo::common::adapter::AdapterManager;
using apollo::common::time::Clock;
using apollo::hdmap::HDMapUtil;
using apollo::hdmap::LaneSegment;
......@@ -49,12 +47,11 @@ Status Destination::ApplyRule(Frame* frame,
return Status::OK();
}
const auto& routing =
AdapterManager::GetRoutingResponse()->GetLatestObserved();
const auto& routing = frame->planning_data().routing;
common::SLPoint dest_sl;
const auto& ref_line = reference_line_info->reference_line();
const auto& routing_end = *routing.routing_request().waypoint().rbegin();
const auto& routing_end = *(routing->routing_request().waypoint().rbegin());
ref_line.XYToSL({routing_end.pose().x(), routing_end.pose().y()}, &dest_sl);
const auto& adc_sl = reference_line_info->AdcSlBoundary();
const auto& dest = GetPlanningStatus()->destination();
......@@ -76,15 +73,14 @@ int Destination::BuildStopDecision(
CHECK_NOTNULL(frame);
CHECK_NOTNULL(reference_line_info);
const auto& routing =
AdapterManager::GetRoutingResponse()->GetLatestObserved();
if (routing.routing_request().waypoint_size() < 2) {
const auto& routing = frame->planning_data().routing;
if (routing->routing_request().waypoint_size() < 2) {
AERROR << "routing_request has no end";
return -1;
}
const auto* planning_status = GetPlanningStatus();
const auto& routing_end = *routing.routing_request().waypoint().rbegin();
const auto& routing_end = *(routing->routing_request().waypoint().rbegin());
double dest_lane_s =
std::max(0.0, routing_end.s() - FLAGS_virtual_stop_wall_length -
config_.destination().stop_distance());
......
......@@ -22,7 +22,6 @@
#include "modules/common/proto/pnc_point.pb.h"
#include "modules/common/adapters/adapter_manager.h"
#include "modules/common/time/time.h"
#include "modules/common/vehicle_state/vehicle_state_provider.h"
#include "modules/planning/common/planning_context.h"
......@@ -31,7 +30,6 @@ namespace apollo {
namespace planning {
using apollo::common::Status;
using apollo::common::adapter::AdapterManager;
using apollo::common::time::Clock;
using apollo::perception::TrafficLight;
using apollo::perception::TrafficLightDetection;
......
......@@ -26,7 +26,7 @@
#include "modules/common/proto/pnc_point.pb.h"
#include "modules/planning/proto/planning_internal.pb.h"
#include "modules/common/adapters/adapter_manager.h"
#include "modules/common/time/time.h"
#include "modules/common/util/map_util.h"
#include "modules/common/vehicle_state/vehicle_state_provider.h"
#include "modules/planning/common/ego_info.h"
......@@ -37,7 +37,7 @@ namespace apollo {
namespace planning {
using apollo::common::Status;
using apollo::common::adapter::AdapterManager;
using apollo::common::time::Clock;
using apollo::common::util::WithinBound;
using apollo::perception::TrafficLight;
using apollo::perception::TrafficLightDetection;
......@@ -50,26 +50,26 @@ Status SignalLight::ApplyRule(Frame* const frame,
if (!FindValidSignalLight(reference_line_info)) {
return Status::OK();
}
ReadSignals();
ReadSignals(frame->planning_data().traffic_light);
MakeDecisions(frame, reference_line_info);
return Status::OK();
}
void SignalLight::ReadSignals() {
void SignalLight::ReadSignals(
const std::shared_ptr<TrafficLightDetection>& traffic_light) {
detected_signals_.clear();
if (AdapterManager::GetTrafficLightDetection()->Empty()) {
if (traffic_light == nullptr) {
return;
}
if (AdapterManager::GetTrafficLightDetection()->GetDelaySec() >
config_.signal_light().signal_expire_time_sec()) {
ADEBUG << "traffic signals msg is expired: "
<< AdapterManager::GetTrafficLightDetection()->GetDelaySec();
const double delay =
traffic_light->header().timestamp_sec() - Clock::NowInSeconds();
if (delay > config_.signal_light().signal_expire_time_sec()) {
ADEBUG << "traffic signals msg is expired, delay = " << delay
<< " seconds.";
return;
}
const TrafficLightDetection& detection =
AdapterManager::GetTrafficLightDetection()->GetLatestObserved();
for (int j = 0; j < detection.traffic_light_size(); j++) {
const TrafficLight& signal = detection.traffic_light(j);
for (int j = 0; j < traffic_light->traffic_light_size(); j++) {
const TrafficLight& signal = traffic_light->traffic_light(j);
detected_signals_[signal.id()] = &signal;
}
}
......
......@@ -41,9 +41,10 @@ class SignalLight : public TrafficRule {
ReferenceLineInfo* const reference_line_info);
private:
void ReadSignals();
void ReadSignals(
const std::shared_ptr<perception::TrafficLightDetection>& traffic_light);
bool FindValidSignalLight(ReferenceLineInfo* const reference_line_info);
apollo::perception::TrafficLight GetSignal(const std::string& signal_id);
perception::TrafficLight GetSignal(const std::string& signal_id);
void MakeDecisions(Frame* const frame,
ReferenceLineInfo* const reference_line_info);
bool BuildStopDecision(Frame* const frame,
......
......@@ -25,7 +25,6 @@
#include "modules/planning/proto/planning_internal.pb.h"
#include "modules/common/adapters/adapter_manager.h"
#include "modules/common/configs/vehicle_config_helper.h"
#include "modules/common/vehicle_state/vehicle_state_provider.h"
#include "modules/planning/common/planning_gflags.h"
......@@ -39,7 +38,6 @@ using apollo::common::ErrorCode;
using apollo::common::Status;
using apollo::common::TrajectoryPoint;
using apollo::common::VehicleConfigHelper;
using apollo::common::adapter::AdapterManager;
using apollo::localization::LocalizationEstimate;
using apollo::planning_internal::STGraphDebug;
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册