mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 02:55:07 +08:00
refactor logger: add an enum for the reason of printing the cpu load
This commit is contained in:
@@ -978,7 +978,7 @@ void Logger::run()
|
|||||||
|
|
||||||
} else {
|
} else {
|
||||||
// delayed stop: we measure the process loads and then stop
|
// delayed stop: we measure the process loads and then stop
|
||||||
initialize_load_output();
|
initialize_load_output(PrintLoadReason::Postflight);
|
||||||
_should_stop_file_log = true;
|
_should_stop_file_log = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -1028,12 +1028,12 @@ void Logger::run()
|
|||||||
|
|
||||||
if (_should_stop_file_log) {
|
if (_should_stop_file_log) {
|
||||||
_should_stop_file_log = false;
|
_should_stop_file_log = false;
|
||||||
write_load_output(false);
|
write_load_output();
|
||||||
stop_log_file();
|
stop_log_file();
|
||||||
continue; // skip to next loop iteration
|
continue; // skip to next loop iteration
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
write_load_output(true);
|
write_load_output();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -1484,7 +1484,7 @@ void Logger::start_log_file()
|
|||||||
|
|
||||||
_start_time_file = hrt_absolute_time();
|
_start_time_file = hrt_absolute_time();
|
||||||
|
|
||||||
initialize_load_output();
|
initialize_load_output(PrintLoadReason::Preflight);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Logger::stop_log_file()
|
void Logger::stop_log_file()
|
||||||
@@ -1520,7 +1520,7 @@ void Logger::start_log_mavlink()
|
|||||||
_writer.unselect_write_backend();
|
_writer.unselect_write_backend();
|
||||||
_writer.notify();
|
_writer.notify();
|
||||||
|
|
||||||
initialize_load_output();
|
initialize_load_output(PrintLoadReason::Preflight);
|
||||||
}
|
}
|
||||||
|
|
||||||
void Logger::stop_log_mavlink()
|
void Logger::stop_log_mavlink()
|
||||||
@@ -1578,18 +1578,26 @@ void Logger::print_load_callback(void *user)
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (callback_data->preflight) {
|
switch (callback_data->logger->_print_load_reason) {
|
||||||
perf_name = "perf_top_preflight";
|
case PrintLoadReason::Preflight:
|
||||||
|
perf_name = "perf_top_preflight";
|
||||||
} else {
|
break;
|
||||||
perf_name = "perf_top_postflight";
|
case PrintLoadReason::Postflight:
|
||||||
|
perf_name = "perf_top_postflight";
|
||||||
|
break;
|
||||||
|
case PrintLoadReason::Watchdog:
|
||||||
|
perf_name = "perf_top_watchdog";
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
perf_name = "perf_top";
|
||||||
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
callback_data->logger->write_info_multiple(perf_name, callback_data->buffer, callback_data->counter != 0);
|
callback_data->logger->write_info_multiple(perf_name, callback_data->buffer, callback_data->counter != 0);
|
||||||
++callback_data->counter;
|
++callback_data->counter;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Logger::initialize_load_output()
|
void Logger::initialize_load_output(PrintLoadReason reason)
|
||||||
{
|
{
|
||||||
perf_callback_data_t callback_data;
|
perf_callback_data_t callback_data;
|
||||||
callback_data.logger = this;
|
callback_data.logger = this;
|
||||||
@@ -1601,16 +1609,16 @@ void Logger::initialize_load_output()
|
|||||||
// this will not yet print anything
|
// this will not yet print anything
|
||||||
print_load_buffer(curr_time, buffer, sizeof(buffer), print_load_callback, &callback_data, &_load);
|
print_load_buffer(curr_time, buffer, sizeof(buffer), print_load_callback, &callback_data, &_load);
|
||||||
_next_load_print = curr_time + 1000000;
|
_next_load_print = curr_time + 1000000;
|
||||||
|
_print_load_reason = reason;
|
||||||
}
|
}
|
||||||
|
|
||||||
void Logger::write_load_output(bool preflight)
|
void Logger::write_load_output()
|
||||||
{
|
{
|
||||||
perf_callback_data_t callback_data = {};
|
perf_callback_data_t callback_data = {};
|
||||||
char buffer[140];
|
char buffer[140];
|
||||||
callback_data.logger = this;
|
callback_data.logger = this;
|
||||||
callback_data.counter = 0;
|
callback_data.counter = 0;
|
||||||
callback_data.buffer = buffer;
|
callback_data.buffer = buffer;
|
||||||
callback_data.preflight = preflight;
|
|
||||||
hrt_abstime curr_time = hrt_absolute_time();
|
hrt_abstime curr_time = hrt_absolute_time();
|
||||||
_writer.set_need_reliable_transfer(true);
|
_writer.set_need_reliable_transfer(true);
|
||||||
// TODO: maybe we should restrict the output to a selected backend (eg. when file logging is running
|
// TODO: maybe we should restrict the output to a selected backend (eg. when file logging is running
|
||||||
|
|||||||
@@ -161,6 +161,12 @@ public:
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
enum class PrintLoadReason {
|
||||||
|
Preflight,
|
||||||
|
Postflight,
|
||||||
|
Watchdog
|
||||||
|
};
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Write an ADD_LOGGED_MSG to the log for a all current subscriptions and instances
|
* Write an ADD_LOGGED_MSG to the log for a all current subscriptions and instances
|
||||||
*/
|
*/
|
||||||
@@ -297,12 +303,12 @@ private:
|
|||||||
/**
|
/**
|
||||||
* initialize the output for the process load, so that ~1 second later it will be written to the log
|
* initialize the output for the process load, so that ~1 second later it will be written to the log
|
||||||
*/
|
*/
|
||||||
void initialize_load_output();
|
void initialize_load_output(PrintLoadReason reason);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* write the process load, which was previously initialized with initialize_load_output()
|
* write the process load, which was previously initialized with initialize_load_output()
|
||||||
*/
|
*/
|
||||||
void write_load_output(bool preflight);
|
void write_load_output();
|
||||||
|
|
||||||
|
|
||||||
static constexpr size_t MAX_TOPICS_NUM = 64; /**< Maximum number of logged topics */
|
static constexpr size_t MAX_TOPICS_NUM = 64; /**< Maximum number of logged topics */
|
||||||
@@ -344,6 +350,7 @@ private:
|
|||||||
will be stopped after load printing */
|
will be stopped after load printing */
|
||||||
print_load_s _load{}; ///< process load data
|
print_load_s _load{}; ///< process load data
|
||||||
hrt_abstime _next_load_print{0}; ///< timestamp when to print the process load
|
hrt_abstime _next_load_print{0}; ///< timestamp when to print the process load
|
||||||
|
PrintLoadReason _print_load_reason;
|
||||||
|
|
||||||
// control
|
// control
|
||||||
param_t _sdlog_profile_handle{PARAM_INVALID};
|
param_t _sdlog_profile_handle{PARAM_INVALID};
|
||||||
|
|||||||
Reference in New Issue
Block a user