Browse Source

AP_Logger: add stream_slowdown to MAV message

c415-sdk
Peter Barker 5 years ago committed by Andrew Tridgell
parent
commit
be6ed0be9f
  1. 3
      libraries/AP_Logger/LogStructure.h

3
libraries/AP_Logger/LogStructure.h

@ -369,6 +369,7 @@ struct PACKED log_MAV { @@ -369,6 +369,7 @@ struct PACKED log_MAV {
uint16_t packet_rx_success_count;
uint16_t packet_rx_drop_count;
uint8_t flags;
uint16_t stream_slowdown_ms;
};
struct PACKED log_RSSI {
@ -1742,7 +1743,7 @@ struct PACKED log_Arm_Disarm { @@ -1742,7 +1743,7 @@ struct PACKED log_Arm_Disarm {
{ LOG_RALLY_MSG, sizeof(log_Rally), \
"RALY", "QBBLLh", "TimeUS,Tot,Seq,Lat,Lng,Alt", "s--DUm", "F--GGB" }, \
{ LOG_MAV_MSG, sizeof(log_MAV), \
"MAV", "QBHHHB", "TimeUS,chan,txp,rxp,rxdp,flags", "s#----", "F-000-" }, \
"MAV", "QBHHHBH", "TimeUS,chan,txp,rxp,rxdp,flags,ss", "s#----s", "F-000-C" }, \
{ LOG_VISUALODOM_MSG, sizeof(log_VisualOdom), \
"VISO", "Qffffffff", "TimeUS,dt,AngDX,AngDY,AngDZ,PosDX,PosDY,PosDZ,conf", "ssrrrmmm-", "FF000000-" }, \
{ LOG_OPTFLOW_MSG, sizeof(log_Optflow), \

Loading…
Cancel
Save