提交 dc101235 编写于 作者: D Dong Li 提交者: Calvin Miao

prediction: added performance profiling support

上级 d42ce3f9
......@@ -17,6 +17,7 @@
#include "modules/common/apollo_app.h"
#include <csignal>
#include <memory>
#include <string>
#include <vector>
......@@ -44,7 +45,7 @@ void ApolloApp::ExportFlags() const {
std::vector<gflags::CommandLineFlagInfo> flags;
gflags::GetAllFlags(&flags);
for (const auto &flag : flags) {
for (const auto& flag : flags) {
fout << "# " << flag.type << ", default=" << flag.default_value << "\n"
<< "# " << flag.description << "\n"
<< "--" << flag.name << "=" << flag.current_value << "\n"
......@@ -53,7 +54,11 @@ void ApolloApp::ExportFlags() const {
}
int ApolloApp::Spin() {
ros::AsyncSpinner spinner(callback_thread_num_);
std::unique_ptr<ros::AsyncSpinner> spinner;
if (callback_thread_num_ > 1) {
spinner = std::unique_ptr<ros::AsyncSpinner>(
new ros::AsyncSpinner(callback_thread_num_));
}
auto status = Init();
if (!status.ok()) {
AERROR << Name() << " Init failed: " << status;
......@@ -65,7 +70,11 @@ int ApolloApp::Spin() {
return -2;
}
ExportFlags();
spinner.start();
if (spinner) {
spinner->start();
} else {
ros::spin();
}
ros::waitForShutdown();
Stop();
AINFO << Name() << " exited.";
......
......@@ -27,6 +27,11 @@ DEFINE_string(prediction_conf_file,
DEFINE_string(prediction_adapter_config_filename,
"modules/prediction/conf/adapter.conf",
"Default conf file for prediction");
DEFINE_bool(prediction_test_mode, false, "Set prediction to test mode");
DEFINE_double(
prediction_test_duration, -1.0,
"The runtime duration in test mode (in seconds). Negative value will not "
"restrict the runtime duration.");
DEFINE_double(prediction_duration, 5.0, "Prediction duration (in seconds)");
DEFINE_double(prediction_period, 0.1, "Prediction period (in seconds");
......
......@@ -24,6 +24,9 @@ DECLARE_string(prediction_module_name);
DECLARE_string(prediction_conf_file);
DECLARE_string(prediction_adapter_config_filename);
DECLARE_bool(prediction_test_mode);
DECLARE_double(prediction_test_duration);
DECLARE_double(prediction_duration);
DECLARE_double(prediction_period);
DECLARE_double(double_precision);
......
......@@ -48,6 +48,8 @@ using ::apollo::perception::PerceptionObstacles;
std::string Prediction::Name() const { return FLAGS_prediction_module_name; }
Status Prediction::Init() {
start_time_ = Clock::NowInSeconds();
// Load prediction conf
prediction_conf_.Clear();
if (!common::util::GetProtoFromFile(FLAGS_prediction_conf_file,
......@@ -129,6 +131,11 @@ void Prediction::OnPlanning(const planning::ADCTrajectory& adc_trajectory) {
}
void Prediction::RunOnce(const PerceptionObstacles& perception_obstacles) {
if (FLAGS_prediction_test_mode && FLAGS_prediction_test_duration > 0 &&
(Clock::NowInSeconds() - start_time_ > FLAGS_prediction_test_duration)) {
AINFO << "Prediction finished running in test mode";
ros::shutdown();
}
ADEBUG << "Received a perception message ["
<< perception_obstacles.ShortDebugString() << "].";
......
......@@ -80,12 +80,13 @@ class Prediction : public PredictionInterface {
void OnLocalization(const localization::LocalizationEstimate &localization);
void OnPlanning(const planning::ADCTrajectory& adc_trajectory);
void OnPlanning(const planning::ADCTrajectory &adc_trajectory);
bool IsValidTrajectoryPoint(
const ::apollo::common::TrajectoryPoint &trajectory_point);
private:
double start_time_ = 0.0;
PredictionConf prediction_conf_;
common::adapter::AdapterManagerConfig adapter_conf_;
};
......
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册