mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 00:05:33 +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
|
@ -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