diff --git a/libraries/AP_Soaring/AP_Soaring.cpp b/libraries/AP_Soaring/AP_Soaring.cpp index 38e9c65034..aa8e0a5854 100644 --- a/libraries/AP_Soaring/AP_Soaring.cpp +++ b/libraries/AP_Soaring/AP_Soaring.cpp @@ -329,7 +329,7 @@ void SoaringController::update_thermalling() // @Field: dx_w: Wind speed north // @Field: dy_w: Wind speed east // @Field: th: Estimate of achievable climbrate in thermal - AP::logger().Write("SOAR", "TimeUS,nettorate,x0,x1,x2,x3,north,east,alt,dx_w,dy_w,th", "Qfffffffffff", + AP::logger().WriteStreaming("SOAR", "TimeUS,nettorate,x0,x1,x2,x3,north,east,alt,dx_w,dy_w,th", "Qfffffffffff", AP_HAL::micros64(), (double)_vario.reading, (double)_ekf.X[0], diff --git a/libraries/AP_Soaring/Variometer.cpp b/libraries/AP_Soaring/Variometer.cpp index 0f81e77e42..3623985cd1 100644 --- a/libraries/AP_Soaring/Variometer.cpp +++ b/libraries/AP_Soaring/Variometer.cpp @@ -90,7 +90,7 @@ void Variometer::update(const float thermal_bank, const float polar_K, const flo // @Field: exs: expected sink rate relative to air in thermalling turn // @Field: dsp: average acceleration along X axis // @Field: dspb: detected bias in average acceleration along X axis - AP::logger().Write("VAR", "TimeUS,aspd_raw,aspd_filt,alt,roll,raw,filt,cl,fc,exs,dsp,dspb", "Qfffffffffff", + AP::logger().WriteStreaming("VAR", "TimeUS,aspd_raw,aspd_filt,alt,roll,raw,filt,cl,fc,exs,dsp,dspb", "Qfffffffffff", AP_HAL::micros64(), (double)0.0, (double)_aspd_filt_constrained,