AP_Compass: mark logger Write() calls as streaming where appropriate

This commit is contained in:
Andrew Tridgell 2021-08-17 19:57:41 +10:00 committed by Peter Barker
parent 730f5cc7e8
commit ffe8add56d
1 changed files with 1 additions and 1 deletions

View File

@ -118,7 +118,7 @@ void CompassLearn::update(void)
// @Field: Yaw: best learnt yaw
// @Field: WVar: error of best learn yaw
// @Field: N: number of samples used
AP::logger().Write("COFS", "TimeUS,OfsX,OfsY,OfsZ,Var,Yaw,WVar,N", "QffffffI",
AP::logger().WriteStreaming("COFS", "TimeUS,OfsX,OfsY,OfsZ,Var,Yaw,WVar,N", "QffffffI",
AP_HAL::micros64(),
(double)best_offsets.x,
(double)best_offsets.y,