@ -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,