logger: publish initial logger_status orb message

This commit is contained in:
Daniel Agar 2020-01-29 17:29:30 -05:00 committed by GitHub
parent 2410b31662
commit 931a3f2684
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
7 changed files with 62 additions and 8 deletions

View File

@ -694,9 +694,9 @@ void statusFTDI() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "dmesg"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "fmu status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "free"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "logger status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener adc_report"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener battery_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener logger_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_accel"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_accel_fifo"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_accel_integrated"'
@ -709,13 +709,14 @@ void statusFTDI() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener sensor_mag"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener servorail_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "listener system_power"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "logger status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ls /"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ls /dev"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ls /etc"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ls /obj"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ls /proc"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "mavlink status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "mavlink status streams"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "mavlink status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "mtd status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param show"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param status"'
@ -743,9 +744,9 @@ void statusSEGGER() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "dmesg"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "fmu status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "free"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "logger status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener adc_report"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener battery_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener logger_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_accel"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_accel_fifo"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_accel_integrated"'
@ -758,13 +759,14 @@ void statusSEGGER() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener sensor_mag"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener servorail_status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "listener system_power"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "logger status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "ls /"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "ls /dev"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "ls /etc"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "ls /obj"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "ls /proc"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "mavlink status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "mavlink status streams"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "mavlink status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "mtd status"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param show"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param status"'

View File

@ -76,6 +76,7 @@ set(msg_files
landing_target_pose.msg
led_control.msg
log_message.msg
logger_status.msg
manual_control_setpoint.msg
mavlink_log.msg
mission.msg

20
msg/logger_status.msg Normal file
View File

@ -0,0 +1,20 @@
uint64 timestamp # time since system start (microseconds)
uint8 LOGGER_TYPE_FULL = 0 # Normal, full size log
uint8 LOGGER_TYPE_MISSION = 1 # reduced mission log (e.g. for geotagging)
uint8 type
uint8 BACKEND_FILE = 1
uint8 BACKEND_MAVLINK = 2
uint8 BACKEND_ALL = 3
uint8 backend
float32 total_written_kb # total written to log in kiloBytes
float32 write_rate_kb_s # write rate in kiloBytes/s
uint32 dropouts # number of failed buffer writes due to buffer overflow
uint32 buffer_used_bytes # current buffer fill in Bytes
uint32 buffer_size_bytes # total buffer size in Bytes
uint8 num_messages

View File

@ -279,6 +279,8 @@ rtps:
id: 124
- msg: vehicle_angular_acceleration
id: 125
- msg: logger_status
id: 126
########## multi topics: begin ##########
- msg: actuator_controls_0
id: 150

View File

@ -96,6 +96,7 @@ void LoggedTopics::add_default_topics()
// multi topics
add_topic_multi("actuator_outputs", 100);
add_topic_multi("logger_status");
add_topic_multi("multirotor_motor_limits", 1000);
add_topic_multi("telemetry_status", 1000);
add_topic_multi("wind_estimate", 1000);

View File

@ -785,11 +785,34 @@ void Logger::run()
_last_sync_time = loop_time;
}
// update buffer statistics
for (int i = 0; i < (int)LogType::Count; ++i) {
if (!_statistics[i].dropout_start && (_writer.get_buffer_fill_count_file((LogType)i) > _statistics[i].high_water)) {
_statistics[i].high_water = _writer.get_buffer_fill_count_file((LogType)i);
// publish logger status
if (hrt_elapsed_time(&_logger_status_last) >= 1_s) {
for (int i = 0; i < (int)LogType::Count; ++i) {
const LogType log_type = static_cast<LogType>(i);
if (_writer.is_started(log_type)) {
const size_t buffer_fill_count_file = _writer.get_buffer_fill_count_file(log_type);
const float kb_written = _writer.get_total_written_file(log_type) / 1024.0f;
const float seconds = hrt_elapsed_time(&_statistics[i].start_time_file) * 1e-6f;
logger_status_s status;
status.type = i;
status.backend = _writer.backend();
status.total_written_kb = kb_written;
status.write_rate_kb_s = kb_written / seconds;
status.dropouts = _statistics[i].write_dropouts;
status.buffer_used_bytes = buffer_fill_count_file;
status.buffer_size_bytes = _writer.get_buffer_size_file(log_type);
status.num_messages = _num_subscriptions;
status.timestamp = hrt_absolute_time();
_logger_status_pub[i].publish(status);
}
}
_logger_status_last = hrt_absolute_time();
}
/* release the log buffer */

View File

@ -44,8 +44,10 @@
#include <systemlib/printload.h>
#include <px4_platform_common/module.h>
#include <uORB/PublicationMulti.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionInterval.hpp>
#include <uORB/topics/logger_status.h>
#include <uORB/topics/log_message.h>
#include <uORB/topics/manual_control_setpoint.h>
#include <uORB/topics/vehicle_command.h>
@ -335,6 +337,9 @@ private:
hrt_abstime _next_load_print{0}; ///< timestamp when to print the process load
PrintLoadReason _print_load_reason {PrintLoadReason::Preflight};
uORB::PublicationMulti<logger_status_s> _logger_status_pub[2] { ORB_ID(logger_status), ORB_ID(logger_status) };
hrt_abstime _logger_status_last{0};
uORB::Subscription _manual_control_sp_sub{ORB_ID(manual_control_setpoint)};
uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)};
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};