diff --git a/modules/common/adapters/adapter_gflags.cc b/modules/common/adapters/adapter_gflags.cc index 77ef2736ee6178fb7cd9b8f24b20cf5f1b2a8fba..2675547c210a84313f2c422a05cd2b303cd038fe 100644 --- a/modules/common/adapters/adapter_gflags.cc +++ b/modules/common/adapters/adapter_gflags.cc @@ -31,7 +31,7 @@ DEFINE_string(planning_trajectory_topic, "/apollo/planning", "planning trajectory topic name"); DEFINE_string(planning_pad_topic, "/apollo/planning/pad", "planning pad topic name"); -DEFINE_string(monitor_topic, "/apollo/monitor", "ROS topic for monitor"); +DEFINE_string(monitor_topic, "/apollo/monitor", "Monitor"); DEFINE_string(pad_topic, "/apollo/control/pad", "control pad message topic name"); DEFINE_string(control_command_topic, "/apollo/control", diff --git a/modules/control/conf/control_conf.pb.txt b/modules/control/conf/control_conf.pb.txt index d65cbe2f374b5505077a57b04634d78050008050..64ef6387d98f72cecc07c42bada94f3ae8227f67 100644 --- a/modules/control/conf/control_conf.pb.txt +++ b/modules/control/conf/control_conf.pb.txt @@ -1,8 +1,3 @@ -chassis_channel: "/apollo/canbus/chassis" -control_command_channel: "/apollo/control" -localization_channel: "/apollo/localization/LocalizationEstimate" -planning_channel: "/apollo/planning/ADCTrajectory" -pad_msg_channel: "/apollo/control/PadMessage" control_test_duration: -1 enable_csv_debug: false enable_speed_station_preview: false diff --git a/modules/control/control_component.cc b/modules/control/control_component.cc index aa8493733568d02dca6005ab9bd509a476b2d0a3..a121b75f7b3fb51aff2cf5da197394c83904e5a9 100644 --- a/modules/control/control_component.cc +++ b/modules/control/control_component.cc @@ -64,15 +64,14 @@ bool ControlComponent::Init() { } chassis_reader_ = node_->CreateReader( - control_conf_.chassis_channel(), - [this](const std::shared_ptr &chassis) { + FLAGS_chassis_topic, [this](const std::shared_ptr &chassis) { ADEBUG << "Received chassis data: run chassis callback."; std::lock_guard lock(mutex_); chassis_.CopyFrom(*chassis); }); trajectory_reader_ = node_->CreateReader( - control_conf_.planning_channel(), + FLAGS_planning_trajectory_topic, [this](const std::shared_ptr &trajectory) { ADEBUG << "Received chassis data: run trajectory callback."; std::lock_guard lock(mutex_); @@ -80,7 +79,7 @@ bool ControlComponent::Init() { }); localization_reader_ = node_->CreateReader( - control_conf_.localization_channel(), + FLAGS_localization_topic, [this](const std::shared_ptr &localization) { ADEBUG << "Received control data: run localization message callback."; std::lock_guard lock(mutex_); @@ -88,14 +87,13 @@ bool ControlComponent::Init() { }); pad_msg_reader_ = node_->CreateReader( - control_conf_.pad_msg_channel(), - [this](const std::shared_ptr &pad_msg) { + FLAGS_pad_topic, [this](const std::shared_ptr &pad_msg) { ADEBUG << "Received control data: run pad message callback."; OnPad(*pad_msg); }); - control_cmd_writer_ = node_->CreateWriter( - control_conf_.control_command_channel()); + control_cmd_writer_ = + node_->CreateWriter(FLAGS_control_command_topic); // set initial vehicle state by cmd // need to sleep, because advertised channel is not ready immediately diff --git a/modules/prediction/prediction_component.cc b/modules/prediction/prediction_component.cc index 75e870454ba5ae7292be0e6136f5a3ceb1a474d4..6388023bc72bf1ea9eef761c6be9d6287216bdf1 100644 --- a/modules/prediction/prediction_component.cc +++ b/modules/prediction/prediction_component.cc @@ -32,13 +32,13 @@ #include "modules/prediction/common/prediction_gflags.h" #include "modules/prediction/common/prediction_map.h" #include "modules/prediction/common/validation_checker.h" -#include "modules/prediction/scenario/scenario_manager.h" #include "modules/prediction/container/container_manager.h" #include "modules/prediction/container/obstacles/obstacles_container.h" #include "modules/prediction/container/pose/pose_container.h" #include "modules/prediction/evaluator/evaluator_manager.h" #include "modules/prediction/predictor/predictor_manager.h" #include "modules/prediction/proto/prediction_obstacle.pb.h" +#include "modules/prediction/scenario/scenario_manager.h" #include "modules/prediction/util/data_extraction.h" namespace apollo { @@ -57,9 +57,7 @@ using apollo::perception::PerceptionObstacle; using apollo::perception::PerceptionObstacles; using apollo::planning::ADCTrajectory; -PredictionComponent::~PredictionComponent() { - Stop(); -} +PredictionComponent::~PredictionComponent() { Stop(); } std::string PredictionComponent::Name() const { return FLAGS_prediction_module_name; @@ -126,12 +124,12 @@ bool PredictionComponent::Init() { } planning_reader_ = node_->CreateReader( - FLAGS_planning_trajectory_topic, - [this](const std::shared_ptr& adc_trajectory) { - ADEBUG << "Received planning data: run planning callback."; - std::lock_guard lock(mutex_); - OnPlanning(*adc_trajectory); - }); + FLAGS_planning_trajectory_topic, + [this](const std::shared_ptr& adc_trajectory) { + ADEBUG << "Received planning data: run planning callback."; + std::lock_guard lock(mutex_); + OnPlanning(*adc_trajectory); + }); // Initialization of all managers ContainerManager::Instance()->Init(adapter_conf_); @@ -170,7 +168,6 @@ bool PredictionComponent::Init() { } Stop(); // TODO(kechxu) accord to cybertron - // ros::shutdown(); } return true; } @@ -209,8 +206,8 @@ bool PredictionComponent::Proc( const std::shared_ptr& perception_obstacles, const std::shared_ptr& localization) { if (FLAGS_prediction_test_mode && - (Clock::NowInSeconds() - component_start_time_ - > FLAGS_prediction_test_duration)) { + (Clock::NowInSeconds() - component_start_time_ > + FLAGS_prediction_test_duration)) { ADEBUG << "Prediction finished running in test mode"; // TODO(kechxu) accord to cybertron // ros::shutdown();