mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Logger: PM msg gets LR field
This commit is contained in:
parent
4c1f2fbde2
commit
ef3ee3d380
@ -537,6 +537,7 @@ struct PACKED log_Rally {
|
|||||||
struct PACKED log_Performance {
|
struct PACKED log_Performance {
|
||||||
LOG_PACKET_HEADER;
|
LOG_PACKET_HEADER;
|
||||||
uint64_t time_us;
|
uint64_t time_us;
|
||||||
|
uint16_t loop_rate;
|
||||||
uint16_t num_long_running;
|
uint16_t num_long_running;
|
||||||
uint16_t num_loops;
|
uint16_t num_loops;
|
||||||
uint32_t max_time;
|
uint32_t max_time;
|
||||||
@ -943,8 +944,9 @@ struct PACKED log_VER {
|
|||||||
// @LoggerMessage: PM
|
// @LoggerMessage: PM
|
||||||
// @Description: autopilot system performance and general data dumping ground
|
// @Description: autopilot system performance and general data dumping ground
|
||||||
// @Field: TimeUS: Time since system startup
|
// @Field: TimeUS: Time since system startup
|
||||||
|
// @Field: LR: Main loop rate
|
||||||
// @Field: NLon: Number of long loops detected
|
// @Field: NLon: Number of long loops detected
|
||||||
// @Field: NLoop: Number of measurement loops for this message
|
// @Field: NL: Number of measurement loops for this message
|
||||||
// @Field: MaxT: Maximum loop time
|
// @Field: MaxT: Maximum loop time
|
||||||
// @Field: Mem: Free memory available
|
// @Field: Mem: Free memory available
|
||||||
// @Field: Load: System processor load
|
// @Field: Load: System processor load
|
||||||
@ -1258,7 +1260,7 @@ LOG_STRUCTURE_FROM_CAMERA \
|
|||||||
LOG_STRUCTURE_FROM_BEACON \
|
LOG_STRUCTURE_FROM_BEACON \
|
||||||
LOG_STRUCTURE_FROM_PROXIMITY \
|
LOG_STRUCTURE_FROM_PROXIMITY \
|
||||||
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance), \
|
{ LOG_PERFORMANCE_MSG, sizeof(log_Performance), \
|
||||||
"PM", "QHHIIHHIIIIII", "TimeUS,NLon,NLoop,MaxT,Mem,Load,ErrL,IntE,ErrC,SPIC,I2CC,I2CI,Ex", "s---b%------s", "F---0A------F" }, \
|
"PM", "QHHHIIHHIIIIII", "TimeUS,LR,NLon,NL,MaxT,Mem,Load,ErrL,IntE,ErrC,SPIC,I2CC,I2CI,Ex", "sz---b%------s", "F----0A------F" }, \
|
||||||
{ LOG_SRTL_MSG, sizeof(log_SRTL), \
|
{ LOG_SRTL_MSG, sizeof(log_SRTL), \
|
||||||
"SRTL", "QBHHBfff", "TimeUS,Active,NumPts,MaxPts,Action,N,E,D", "s----mmm", "F----000" }, \
|
"SRTL", "QBHHBfff", "TimeUS,Active,NumPts,MaxPts,Action,N,E,D", "s----mmm", "F----000" }, \
|
||||||
LOG_STRUCTURE_FROM_AVOIDANCE \
|
LOG_STRUCTURE_FROM_AVOIDANCE \
|
||||||
|
Loading…
Reference in New Issue
Block a user