mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 20:10:18 +03:00
Finally rename flight.c/.h to pid.c/.h. Cleanup some dependencies.
Relocate more code.
This commit is contained in:
parent
8cc9e8ca37
commit
55cac2bdeb
32 changed files with 101 additions and 93 deletions
2
Makefile
2
Makefile
|
@ -203,7 +203,7 @@ COMMON_SRC = build_config.c \
|
|||
mw.c \
|
||||
flight/altitudehold.c \
|
||||
flight/failsafe.c \
|
||||
flight/flight.c \
|
||||
flight/pid.c \
|
||||
flight/imu.c \
|
||||
flight/mixer.c \
|
||||
drivers/bus_i2c_soft.c \
|
||||
|
|
|
@ -58,14 +58,15 @@
|
|||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/flight.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/altitudehold.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
#include "config/config_master.h"
|
||||
|
||||
|
|
|
@ -35,14 +35,15 @@
|
|||
#include "sensors/barometer.h"
|
||||
#include "sensors/sonar.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/flight.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/escservo.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
extern int16_t debug[4];
|
||||
|
|
|
@ -15,10 +15,9 @@
|
|||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "flight/flight.h"
|
||||
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "sensors/barometer.h"
|
||||
|
||||
|
|
|
@ -34,7 +34,7 @@
|
|||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "config/config.h"
|
||||
|
|
|
@ -40,7 +40,7 @@
|
|||
#include "sensors/sonar.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/flight.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
|
|
@ -43,7 +43,7 @@
|
|||
#include "sensors/acceleration.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/flight.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
|
|
@ -25,31 +25,31 @@
|
|||
#include "platform.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/serial_uart.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/light_led.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "flight/flight.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/rc_controls.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "flight/gps_conversion.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
#include "flight/gps_conversion.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
|
||||
#include "flight/navigation.h"
|
||||
extern int16_t magHold;
|
||||
|
||||
#ifdef GPS
|
||||
|
||||
|
@ -57,8 +57,6 @@ extern int16_t debug[4];
|
|||
|
||||
bool areSticksInApModePosition(uint16_t ap_mode);
|
||||
|
||||
int16_t magHold;
|
||||
|
||||
// **********************
|
||||
// GPS
|
||||
// **********************
|
||||
|
|
|
@ -17,8 +17,6 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
extern int16_t magHold;
|
||||
|
||||
// navigation mode
|
||||
typedef enum {
|
||||
NAV_MODE_NONE = 0,
|
||||
|
|
|
@ -38,7 +38,7 @@
|
|||
#include "io/rc_controls.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "flight/autotune.h"
|
|
@ -48,7 +48,7 @@
|
|||
|
||||
#include "io/rc_controls.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#ifdef GPS
|
||||
|
|
|
@ -27,30 +27,26 @@
|
|||
#include "build_config.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "drivers/serial_uart.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/light_led.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "flight/flight.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
#include "flight/gps_conversion.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/display.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "flight/gps_conversion.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
|
||||
#ifdef GPS
|
||||
|
|
|
@ -28,24 +28,26 @@
|
|||
#ifdef LED_STRIP
|
||||
|
||||
#include <common/color.h>
|
||||
#include <common/maths.h>
|
||||
#include <common/typeconversion.h>
|
||||
|
||||
#include "drivers/light_ws2811strip.h"
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include <common/maths.h>
|
||||
#include <common/printf.h>
|
||||
#include <common/typeconversion.h>
|
||||
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
|
||||
#include "io/ledstrip.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
static bool ledStripInitialised = false;
|
||||
static bool ledStripEnabled = true;
|
||||
|
|
|
@ -30,7 +30,6 @@
|
|||
#include "config/runtime_config.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
|
||||
|
@ -40,15 +39,15 @@
|
|||
#include "sensors/gyro.h"
|
||||
#include "sensors/acceleration.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
#include "io/beeper.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "mw.h"
|
||||
|
|
|
@ -64,7 +64,7 @@
|
|||
#include "sensors/compass.h"
|
||||
#include "sensors/barometer.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation.h"
|
||||
|
|
|
@ -62,13 +62,15 @@
|
|||
#include "sensors/compass.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "flight/altitudehold.h"
|
||||
|
||||
#include "mw.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -69,7 +69,7 @@
|
|||
#include "telemetry/telemetry.h"
|
||||
#include "blackbox/blackbox.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/failsafe.h"
|
||||
|
|
|
@ -66,10 +66,10 @@
|
|||
#include "blackbox/blackbox.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/flight.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/altitudehold.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/autotune.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
|
@ -94,6 +94,8 @@ int16_t debug[4];
|
|||
uint32_t currentTime = 0;
|
||||
uint32_t previousTime = 0;
|
||||
uint16_t cycleTime = 0; // this is the number in micro second to achieve a full loop, it can differ a little and is taken into account in the PID loop
|
||||
|
||||
int16_t magHold;
|
||||
int16_t headFreeModeHold;
|
||||
|
||||
int16_t telemTemperature1; // gyro sensor temperature
|
||||
|
|
|
@ -17,6 +17,8 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
extern int16_t magHold;
|
||||
|
||||
void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsDelta);
|
||||
void handleInflightCalibrationStickPosition();
|
||||
|
||||
|
|
|
@ -28,7 +28,6 @@
|
|||
#include "drivers/gpio.h"
|
||||
#include "drivers/light_led.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
|
|
@ -25,7 +25,6 @@
|
|||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "flight/flight.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "io/statusindicator.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
|
|
|
@ -52,7 +52,6 @@
|
|||
#include "drivers/gpio.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
|
|
@ -28,8 +28,6 @@
|
|||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/sonar.h"
|
||||
|
||||
|
|
|
@ -51,7 +51,7 @@
|
|||
#include "rx/rx.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/flight.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/altitudehold.h"
|
||||
|
||||
|
|
|
@ -74,7 +74,7 @@
|
|||
#include "sensors/sensors.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
|
|
|
@ -45,7 +45,7 @@
|
|||
#include "sensors/compass.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/failsafe.h"
|
||||
|
|
|
@ -24,25 +24,27 @@
|
|||
|
||||
extern "C" {
|
||||
#include "common/axis.h"
|
||||
#include "flight/flight.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/mixer.h"
|
||||
|
||||
#include "io/escservo.h"
|
||||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/altitudehold.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
}
|
||||
|
||||
#include "unittest_macros.h"
|
||||
|
@ -148,7 +150,7 @@ uint8_t armingFlags;
|
|||
int32_t sonarAlt;
|
||||
|
||||
|
||||
void gyroGetADC(void) {};
|
||||
void gyroUpdate(void) {};
|
||||
bool sensors(uint32_t mask)
|
||||
{
|
||||
UNUSED(mask);
|
||||
|
@ -159,7 +161,7 @@ void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims)
|
|||
UNUSED(rollAndPitchTrims);
|
||||
}
|
||||
|
||||
void accSum_reset(void) {};
|
||||
void imuResetAccelerationSum(void) {};
|
||||
|
||||
int32_t applyDeadband(int32_t, int32_t) { return 0; }
|
||||
uint32_t micros(void) { return 0; }
|
||||
|
|
|
@ -25,7 +25,6 @@
|
|||
extern "C" {
|
||||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
#include "flight/flight.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "drivers/sensor.h"
|
||||
|
@ -39,6 +38,7 @@ extern "C" {
|
|||
#include "config/runtime_config.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
}
|
||||
|
||||
|
@ -53,19 +53,19 @@ TEST(FlightImuTest, TestCalculateHeading)
|
|||
{
|
||||
//TODO: Add test cases using the Z dimension.
|
||||
t_fp_vector north = {.A={1.0f, 0.0f, 0.0f}};
|
||||
EXPECT_EQ(calculateHeading(&north), 0);
|
||||
EXPECT_EQ(imuCalculateHeading(&north), 0);
|
||||
|
||||
t_fp_vector east = {.A={0.0f, 1.0f, 0.0f}};
|
||||
EXPECT_EQ(calculateHeading(&east), 90);
|
||||
EXPECT_EQ(imuCalculateHeading(&east), 90);
|
||||
|
||||
t_fp_vector south = {.A={-1.0f, 0.0f, 0.0f}};
|
||||
EXPECT_EQ(calculateHeading(&south), 180);
|
||||
EXPECT_EQ(imuCalculateHeading(&south), 180);
|
||||
|
||||
t_fp_vector west = {.A={0.0f, -1.0f, 0.0f}};
|
||||
EXPECT_EQ(calculateHeading(&west), 270);
|
||||
EXPECT_EQ(imuCalculateHeading(&west), 270);
|
||||
|
||||
t_fp_vector north_east = {.A={1.0f, 1.0f, 0.0f}};
|
||||
EXPECT_EQ(calculateHeading(&north_east), 45);
|
||||
EXPECT_EQ(imuCalculateHeading(&north_east), 45);
|
||||
}
|
||||
|
||||
// STUBS
|
||||
|
@ -86,9 +86,12 @@ uint16_t flightModeFlags;
|
|||
uint8_t armingFlags;
|
||||
|
||||
int32_t sonarAlt;
|
||||
int16_t accADC[XYZ_AXIS_COUNT];
|
||||
int16_t gyroADC[XYZ_AXIS_COUNT];
|
||||
|
||||
|
||||
void gyroGetADC(void) {};
|
||||
|
||||
void gyroUpdate(void) {};
|
||||
bool sensors(uint32_t mask)
|
||||
{
|
||||
UNUSED(mask);
|
||||
|
|
|
@ -24,7 +24,6 @@ extern "C" {
|
|||
|
||||
#include "common/color.h"
|
||||
#include "common/axis.h"
|
||||
#include "flight/flight.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "config/runtime_config.h"
|
||||
|
|
|
@ -20,14 +20,24 @@
|
|||
|
||||
extern "C" {
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/maths.h"
|
||||
#include "common/axis.h"
|
||||
#include "flight/flight.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
}
|
||||
|
||||
#include "unittest_macros.h"
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
|
|
|
@ -27,22 +27,21 @@ extern "C" {
|
|||
#include "common/axis.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "io/gps.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/hott.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/gps_conversion.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
}
|
||||
|
||||
#include "unittest_macros.h"
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue