AP_OpticalFlow: add some units to OFCA log message

Mainly just to get the instance column to make graphing axes easier

pbarker@fx:~/rc/ardupilot(master)$ mavlogdump.py logs/00000003.BIN --t FMTU | grep 251
2022-12-12 09:41:47.06: FMTU {TimeUS : 62248424, FmtType : 251, UnitIds : s#-???, MultIds : F00000}
pbarker@fx:~/rc/ardupilot(master)$ mavlogdump.py logs/00000003.BIN --t FMT | grep OFCA
2022-12-12 09:41:46.48: FMT {Type : 251, Length : 25, Name : OFCA, Format : QBBfff, Columns : TimeUS,Axis,Num,FRate,BRate,LPred}

MAV> graph OFCA[1].
OFCA[1].Axis    OFCA[1].BRate   OFCA[1].FRate   OFCA[1].LPred   OFCA[1].Num     OFCA[1].TimeUS
MAV> graph OFCA[1].LPred
This commit is contained in:
Peter Barker 2022-12-12 09:46:34 +11:00 committed by Peter Barker
parent 8dff38a4a1
commit e06a0c6876
1 changed files with 6 additions and 1 deletions

View File

@ -310,7 +310,12 @@ void AP_OpticalFlow_Calibrator::log_sample(uint8_t axis, uint8_t sample_num, flo
// @Field: BRate: Body rate
// @Field: LPred: Los pred
AP::logger().Write("OFCA", "TimeUS,Axis,Num,FRate,BRate,LPred", "QBBfff",
AP::logger().Write(
"OFCA",
"TimeUS,Axis,Num,FRate,BRate,LPred",
"s#-EEE",
"F00000",
"QBBfff",
AP_HAL::micros64(),
(unsigned)axis,
(unsigned)sample_num,