AP_HAL_SITL: fix possible divide by 0 on synth.hpp

This commit is contained in:
Pierre Kancir 2023-08-23 09:03:51 +02:00 committed by Andrew Tridgell
parent b3954afe52
commit d78fe1ad99
1 changed files with 2 additions and 1 deletions

View File

@ -7,6 +7,7 @@
// Headers
////////////////////////////////////////////////////////////
#include <SFML/Audio.hpp>
#include <cfloat>
#include <cmath>
namespace Synth
@ -107,7 +108,7 @@ double amplitude(double dTime, sEnvelope env)
else if (dTime > env.dAttackTime && dTime <= (env.dAttackTime + env.dDecayTime)) // Decay phase
dAmplitude = ((dTime - env.dAttackTime) / env.dDecayTime) * (env.dSustainAmplitude - env.dStartAmplitude) + env.dStartAmplitude;
else if (dTime <= env.dAttackTime) // Attack phase
else if ((env.dAttackTime >= DBL_EPSILON) && dTime <= env.dAttackTime) // Attack phase
dAmplitude = (dTime / env.dAttackTime) * env.dStartAmplitude;
// Amplitude should not be negative, check just in case