mirror of https://github.com/ArduPilot/ardupilot
AP_DroneCAN: document CANS (Can Bus Statistics) log message
This commit is contained in:
parent
7c1cc26509
commit
4554dd28d3
|
@ -1953,6 +1953,24 @@ void AP_DroneCAN::logging(void)
|
|||
return;
|
||||
}
|
||||
const auto &s = *stats;
|
||||
|
||||
// @LoggerMessage: CANS
|
||||
// @Description: CAN Bus Statistics
|
||||
// @Field: TimeUS: Time since system startup
|
||||
// @Field: I: driver index
|
||||
// @Field: T: transmit success count
|
||||
// @Field: Trq: transmit request count
|
||||
// @Field: Trej: transmit reject count
|
||||
// @Field: Tov: transmit overflow count
|
||||
// @Field: Tto: transmit timeout count
|
||||
// @Field: Tab: transmit abort count
|
||||
// @Field: R: receive count
|
||||
// @Field: Rov: receive overflow count
|
||||
// @Field: Rer: receive error count
|
||||
// @Field: Bo: bus offset error count
|
||||
// @Field: Etx: ESC successful send count
|
||||
// @Field: Stx: Servo successful send count
|
||||
// @Field: Ftx: ESC/Servo failed-to-send count
|
||||
AP::logger().WriteStreaming("CANS",
|
||||
"TimeUS,I,T,Trq,Trej,Tov,Tto,Tab,R,Rov,Rer,Bo,Etx,Stx,Ftx",
|
||||
"s#-------------",
|
||||
|
|
Loading…
Reference in New Issue