mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_Notify: Change division to multiplication
This commit is contained in:
parent
48ab08fb67
commit
dee040b14a
@ -114,7 +114,7 @@ float MMLPlayer::rest_duration(uint32_t rest_length, uint8_t dots) const
|
||||
}
|
||||
|
||||
float rest_period = whole_note_period/rest_length;
|
||||
float dot_extension = rest_period/2;
|
||||
float dot_extension = rest_period * 0.5f;
|
||||
|
||||
while (dots--) {
|
||||
rest_period += dot_extension;
|
||||
@ -299,7 +299,7 @@ void MMLPlayer::next_action()
|
||||
}
|
||||
note_period -= _silence_duration;
|
||||
|
||||
float dot_extension = note_period/2;
|
||||
float dot_extension = note_period * 0.5f;
|
||||
uint8_t dots = next_dots();
|
||||
while (dots--) {
|
||||
note_period += dot_extension;
|
||||
|
Loading…
Reference in New Issue
Block a user