From b4b2024982dc3845be7742c22e7ec4a4c1437887 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Wed, 9 Mar 2022 08:53:58 +1100 Subject: [PATCH] AP_Math: fixed build error on cygwin ensure variables are always initialised --- libraries/AP_Math/SCurve.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/libraries/AP_Math/SCurve.cpp b/libraries/AP_Math/SCurve.cpp index 42a14ca797..5d60eacd03 100644 --- a/libraries/AP_Math/SCurve.cpp +++ b/libraries/AP_Math/SCurve.cpp @@ -622,11 +622,12 @@ void SCurve::advance_time(float dt) // calculate the jerk, acceleration, velocity and position at the provided time void SCurve::get_jerk_accel_vel_pos_at_time(float time_now, float &Jt_out, float &At_out, float &Vt_out, float &Pt_out) const { + // start with zeros as function is void and we want to guarantee all outputs are initialised + Jt_out = 0; + At_out = 0; + Vt_out = 0; + Pt_out = 0; if (num_segs != segments_max) { - Jt_out = 0; - At_out = 0; - Vt_out = 0; - Pt_out = 0; return; }