diff --git a/libraries/AP_Landing/AP_Landing_Slope.cpp b/libraries/AP_Landing/AP_Landing_Slope.cpp index 657dedb19d..34aedcff3e 100644 --- a/libraries/AP_Landing/AP_Landing_Slope.cpp +++ b/libraries/AP_Landing/AP_Landing_Slope.cpp @@ -409,7 +409,7 @@ void AP_Landing::type_slope_log(void) const // @Field: slopeInit: Initial slope to landing point // @Field: altO: Rangefinder correction // @Field: fh: Height for flare timing. - AP::logger().Write("LAND", "TimeUS,stage,f1,f2,slope,slopeInit,altO,fh", "QBBBffff", + AP::logger().WriteStreaming("LAND", "TimeUS,stage,f1,f2,slope,slopeInit,altO,fh", "QBBBffff", AP_HAL::micros64(), type_slope_stage, flags,