Add the first unit test for the mixer.
[betaflight.git] / src / test / unit / flight_mixer_unittest.cc
blob386db1d2b85ee70e18767f0c252e0a36e31d9424
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdint.h>
19 #include <stdbool.h>
21 #include <limits.h>
23 extern "C" {
24 #include "platform.h"
26 #include "common/axis.h"
27 #include "common/maths.h"
29 #include "drivers/sensor.h"
30 #include "drivers/accgyro.h"
32 #include "sensors/sensors.h"
33 #include "sensors/acceleration.h"
35 #include "rx/rx.h"
36 #include "flight/pid.h"
37 #include "flight/imu.h"
38 #include "flight/mixer.h"
39 #include "flight/lowpass.h"
41 #include "io/rc_controls.h"
43 extern uint8_t servoCount;
44 void forwardAuxChannelsToServos(void);
48 #include "unittest_macros.h"
49 #include "gtest/gtest.h"
51 typedef struct motor_s {
52 uint16_t value;
53 } motor_t;
55 typedef struct servo_s {
56 uint16_t value;
57 } servo_t;
59 motor_t motors[MAX_SUPPORTED_MOTORS];
60 servo_t servos[MAX_SUPPORTED_SERVOS];
62 uint8_t lastOneShotUpdateMotorCount;
65 TEST(FlightMixerTest, TestForwardAuxChannelsToServosWithNoServos)
67 // given
68 memset(&motors, 0, sizeof(motors));
69 memset(&servos, 0, sizeof(servos));
70 servoCount = 0;
72 rcData[AUX1] = 1500;
73 rcData[AUX2] = 1500;
74 rcData[AUX3] = 1500;
75 rcData[AUX4] = 1500;
77 // when
78 forwardAuxChannelsToServos();
80 // then
81 for (uint8_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
82 EXPECT_EQ(servos[i].value, 0);
86 // STUBS
88 extern "C" {
89 rollAndPitchInclination_t inclination;
90 rxRuntimeConfig_t rxRuntimeConfig;
92 int16_t axisPID[XYZ_AXIS_COUNT];
93 int16_t rcCommand[4];
94 int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
96 uint32_t rcModeActivationMask;
97 int16_t debug[4];
99 uint8_t stateFlags;
100 uint16_t flightModeFlags;
101 uint8_t armingFlags;
103 void delay(uint32_t) {}
105 bool feature(uint32_t) {
106 return true;
109 int32_t lowpassFixed(lowpass_t *, int32_t, int16_t) {
110 return 0;
113 void pwmWriteMotor(uint8_t index, uint16_t value) {
114 motors[index].value = value;
117 void pwmCompleteOneshotMotorUpdate(uint8_t motorCount) {
118 lastOneShotUpdateMotorCount = motorCount;
121 void pwmWriteServo(uint8_t index, uint16_t value) {
122 servos[index].value = value;