From ff4b63f9dcd4460e0a374443983efc124a6e9a42 Mon Sep 17 00:00:00 2001 From: Iampete1 Date: Sun, 30 Apr 2023 13:27:37 +0100 Subject: [PATCH] AP_Math: Chirp: add complete method to see if chirp is finished --- libraries/AP_Math/chirp.cpp | 5 +++++ libraries/AP_Math/chirp.h | 6 ++++++ 2 files changed, 11 insertions(+) diff --git a/libraries/AP_Math/chirp.cpp b/libraries/AP_Math/chirp.cpp index b01250bca6..eb3c7e2fff 100644 --- a/libraries/AP_Math/chirp.cpp +++ b/libraries/AP_Math/chirp.cpp @@ -46,6 +46,8 @@ void Chirp::init(float time_record, float frequency_start_hz, float frequency_st B = logf(wMax / wMin); + // Mark as incomplete + complete = false; } // determine chirp signal output at the specified time and amplitude @@ -83,5 +85,8 @@ float Chirp::update(float time, float waveform_magnitude) waveform_freq_rads = wMax; output = 0.0f; } + + complete = time > record; + return output; } diff --git a/libraries/AP_Math/chirp.h b/libraries/AP_Math/chirp.h index 23487e21e5..0208503293 100644 --- a/libraries/AP_Math/chirp.h +++ b/libraries/AP_Math/chirp.h @@ -16,6 +16,9 @@ public: // accessor for the current waveform frequency float get_frequency_rads() {return waveform_freq_rads; } + // Return true if chirp is completed + bool completed() const { return complete; } + private: // Total chirp length in seconds float record; @@ -50,4 +53,7 @@ private: // output of chirp signal at the requested time float output; + // True if chirp is complete, reset to false on init + bool complete; + };