mirror of https://github.com/ArduPilot/ardupilot
AP_Math: Chirp: add complete method to see if chirp is finished
This commit is contained in:
parent
8a4b30ec3f
commit
ff4b63f9dc
|
@ -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;
|
||||
}
|
||||
|
|
|
@ -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;
|
||||
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue