Dshot RPM Telemetry Refactoring (#13012)
[betaflight.git] / src / main / io / pidaudio.c
blob26be198290f2108f05be9dd6267fe2c2d199e6f5
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 #include <stdbool.h>
22 #include <stdint.h>
23 #include <math.h>
25 #include "platform.h"
27 #include "common/axis.h"
28 #include "common/maths.h"
30 #include "drivers/audio.h"
32 #include "fc/rc_modes.h"
34 #include "flight/pid.h"
36 #include "io/pidaudio.h"
38 static bool pidAudioEnabled = false;
40 static pidAudioModes_e pidAudioMode = PID_AUDIO_PIDSUM_XY;
42 void pidAudioInit(void)
44 audioSetupIO();
47 void pidAudioStart(void)
49 audioGenerateWhiteNoise();
52 void pidAudioStop(void)
54 audioSilence();
57 pidAudioModes_e pidAudioGetMode(void)
59 return pidAudioMode;
62 void pidAudioSetMode(pidAudioModes_e mode)
64 pidAudioMode = mode;
67 void FAST_CODE_NOINLINE pidAudioUpdate(void)
69 bool newState = IS_RC_MODE_ACTIVE(BOXPIDAUDIO);
71 if (pidAudioEnabled != newState) {
72 if (newState) {
73 pidAudioStart();
74 } else {
75 pidAudioStop();
77 pidAudioEnabled = newState;
80 if (!pidAudioEnabled) {
81 return;
84 uint8_t tone = TONE_MID;
86 switch (pidAudioMode) {
87 case PID_AUDIO_PIDSUM_X:
89 const uint32_t pidSumX = MIN(fabsf(pidData[FD_ROLL].Sum), PIDSUM_LIMIT);
90 tone = scaleRange(pidSumX, 0, PIDSUM_LIMIT, TONE_MAX, TONE_MIN);
91 break;
93 case PID_AUDIO_PIDSUM_Y:
95 const uint32_t pidSumY = MIN(fabsf(pidData[FD_PITCH].Sum), PIDSUM_LIMIT);
96 tone = scaleRange(pidSumY, 0, PIDSUM_LIMIT, TONE_MAX, TONE_MIN);
97 break;
99 case PID_AUDIO_PIDSUM_XY:
101 const uint32_t pidSumXY = MIN((fabsf(pidData[FD_ROLL].Sum) + fabsf(pidData[FD_PITCH].Sum)) / 2, PIDSUM_LIMIT);
102 tone = scaleRange(pidSumXY, 0, PIDSUM_LIMIT, TONE_MAX, TONE_MIN);
103 break;
105 default:
106 break;
109 audioPlayTone(tone);