mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 05:15:25 +03:00
Relocate some structures and code to the right places.
This cleans up the include file order somewhat and fixes a couple of dependencies. The goal of this is to rename flight.c/flight.h to pid.c/pid.h.
This commit is contained in:
parent
a9b2c39872
commit
53406a7ac7
20 changed files with 198 additions and 145 deletions
|
@ -36,7 +36,6 @@
|
|||
#include "drivers/light_led.h"
|
||||
#include "drivers/sound_beeper.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/sonar.h"
|
||||
|
@ -45,17 +44,11 @@
|
|||
#include "sensors/barometer.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/display.h"
|
||||
#include "io/escservo.h"
|
||||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/altitudehold.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/autotune.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
@ -63,9 +56,18 @@
|
|||
#include "io/serial_cli.h"
|
||||
#include "io/serial_msp.h"
|
||||
#include "io/statusindicator.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/altitudehold.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -21,24 +21,19 @@
|
|||
#include "drivers/light_led.h"
|
||||
#include "drivers/sound_beeper.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/display.h"
|
||||
#include "io/escservo.h"
|
||||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/altitudehold.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/autotune.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
@ -50,6 +45,12 @@
|
|||
#include "telemetry/telemetry.h"
|
||||
#include "common/printf.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/altitudehold.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -27,38 +27,38 @@
|
|||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/compass.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/gpio.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/compass.h"
|
||||
|
||||
#include "io/statusindicator.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "drivers/serial.h"
|
||||
#include "io/serial.h"
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/statusindicator.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/flight.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/altitudehold.h"
|
||||
#include "flight/imu.h"
|
||||
|
|
|
@ -40,6 +40,10 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode);
|
|||
uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode);
|
||||
|
||||
static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
||||
#if !defined(INVERTER) && !defined(STM32F303xC)
|
||||
UNUSED(uartPort);
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER
|
||||
if (uartPort->port.inversion == SERIAL_INVERTED && uartPort->USARTx == INVERTER_USART) {
|
||||
// Enable hardware inverter if available.
|
||||
|
|
|
@ -30,14 +30,13 @@
|
|||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/sonar.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/flight.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
|
|
@ -28,8 +28,14 @@
|
|||
#include "common/maths.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "config/config.h"
|
||||
#include "blackbox/blackbox.h"
|
||||
|
|
|
@ -26,20 +26,24 @@
|
|||
#include "common/axis.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/acceleration.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "flight/autotune.h"
|
||||
#include "io/gps.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
extern uint16_t cycleTime;
|
||||
extern uint8_t motorCount;
|
||||
|
@ -65,12 +69,6 @@ typedef void (*pidControllerFuncPtr)(pidProfile_t *pidProfile, controlRateConfig
|
|||
|
||||
pidControllerFuncPtr pid_controller = pidMultiWii; // which pid controller are we using, defaultMultiWii
|
||||
|
||||
void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims)
|
||||
{
|
||||
rollAndPitchTrims->values.roll = 0;
|
||||
rollAndPitchTrims->values.pitch = 0;
|
||||
}
|
||||
|
||||
void resetErrorAngle(void)
|
||||
{
|
||||
errorAngleI[ROLL] = 0;
|
||||
|
|
|
@ -65,44 +65,9 @@ typedef enum {
|
|||
|
||||
#define FLIGHT_DYNAMICS_INDEX_COUNT 3
|
||||
|
||||
typedef struct int16_flightDynamicsTrims_s {
|
||||
int16_t roll;
|
||||
int16_t pitch;
|
||||
int16_t yaw;
|
||||
} flightDynamicsTrims_def_t;
|
||||
|
||||
typedef union {
|
||||
int16_t raw[3];
|
||||
flightDynamicsTrims_def_t values;
|
||||
} flightDynamicsTrims_t;
|
||||
|
||||
typedef struct rollAndPitchTrims_s {
|
||||
int16_t roll;
|
||||
int16_t pitch;
|
||||
} rollAndPitchTrims_t_def;
|
||||
|
||||
typedef union {
|
||||
int16_t raw[2];
|
||||
rollAndPitchTrims_t_def values;
|
||||
} rollAndPitchTrims_t;
|
||||
|
||||
typedef struct rollAndPitchInclination_s {
|
||||
// absolute angle inclination in multiple of 0.1 degree 180 deg = 1800
|
||||
int16_t rollDeciDegrees;
|
||||
int16_t pitchDeciDegrees;
|
||||
} rollAndPitchInclination_t_def;
|
||||
|
||||
typedef union {
|
||||
int16_t raw[ANGLE_INDEX_COUNT];
|
||||
rollAndPitchInclination_t_def values;
|
||||
} rollAndPitchInclination_t;
|
||||
|
||||
|
||||
#define DEGREES_TO_DECIDEGREES(angle) (angle * 10)
|
||||
#define DECIDEGREES_TO_DEGREES(angle) (angle / 10.0f)
|
||||
|
||||
extern rollAndPitchInclination_t inclination;
|
||||
|
||||
extern int16_t gyroData[FLIGHT_DYNAMICS_INDEX_COUNT];
|
||||
extern int16_t gyroZero[FLIGHT_DYNAMICS_INDEX_COUNT];
|
||||
|
||||
|
@ -118,7 +83,6 @@ extern int32_t AltHold;
|
|||
extern int32_t vario;
|
||||
|
||||
void setPIDController(int type);
|
||||
void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims);
|
||||
void resetErrorAngle(void);
|
||||
void resetErrorGyro(void);
|
||||
|
||||
|
|
|
@ -26,11 +26,8 @@
|
|||
#include <platform.h>
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "flight/flight.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/compass.h"
|
||||
|
@ -42,14 +39,16 @@
|
|||
#include "sensors/barometer.h"
|
||||
#include "sensors/sonar.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/flight.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
extern int16_t debug[4];
|
||||
|
||||
int16_t gyroADC[XYZ_AXIS_COUNT], accADC[XYZ_AXIS_COUNT], accSmooth[XYZ_AXIS_COUNT];
|
||||
int16_t gyroADC[XYZ_AXIS_COUNT], accSmooth[XYZ_AXIS_COUNT];
|
||||
int32_t accSum[XYZ_AXIS_COUNT];
|
||||
|
||||
uint32_t accTimeSum = 0; // keep track for integration of acc
|
||||
|
@ -311,7 +310,7 @@ void imuUpdate(rollAndPitchTrims_t *accelerometerTrims, uint8_t mixerMode)
|
|||
|
||||
gyroUpdate();
|
||||
if (sensors(SENSOR_ACC)) {
|
||||
updateAccelerationReadings(accelerometerTrims);
|
||||
updateAccelerationReadings(accelerometerTrims); // TODO rename to accelerometerUpdate and rename many other 'Acceleration' references to be 'Accelerometer'
|
||||
imuCalculateEstimatedAttitude();
|
||||
} else {
|
||||
accADC[X] = 0;
|
||||
|
|
|
@ -22,6 +22,24 @@ extern uint32_t accTimeSum;
|
|||
extern int accSumCount;
|
||||
extern float accVelScale;
|
||||
|
||||
typedef struct rollAndPitchInclination_s {
|
||||
// absolute angle inclination in multiple of 0.1 degree 180 deg = 1800
|
||||
int16_t rollDeciDegrees;
|
||||
int16_t pitchDeciDegrees;
|
||||
} rollAndPitchInclination_t_def;
|
||||
|
||||
typedef union {
|
||||
int16_t raw[ANGLE_INDEX_COUNT];
|
||||
rollAndPitchInclination_t_def values;
|
||||
} rollAndPitchInclination_t;
|
||||
|
||||
extern rollAndPitchInclination_t inclination;
|
||||
|
||||
typedef struct accDeadband_s {
|
||||
uint8_t xy; // set the acc deadband for xy-Axis
|
||||
uint8_t z; // set the acc deadband for z-Axis, this ignores small accelerations
|
||||
} accDeadband_t;
|
||||
|
||||
typedef struct imuRuntimeConfig_s {
|
||||
uint8_t acc_lpf_factor;
|
||||
uint8_t acc_unarmedcal;
|
||||
|
@ -47,3 +65,5 @@ float calculateAccZLowPassFilterRCTimeConstant(float accz_lpf_cutoff);
|
|||
int16_t imuCalculateHeading(t_fp_vector *vec);
|
||||
|
||||
void imuResetAccelerationSum(void);
|
||||
|
||||
|
||||
|
|
|
@ -30,14 +30,21 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/gimbal.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/acceleration.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/flight.h"
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
|
|
|
@ -31,9 +31,6 @@
|
|||
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
|
||||
|
@ -45,13 +42,18 @@
|
|||
|
||||
#include "io/gps.h"
|
||||
#include "io/beeper.h"
|
||||
#include "mw.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/navigation.h"
|
||||
|
||||
#include "mw.h"
|
||||
|
||||
|
||||
static escAndServoConfig_t *escAndServoConfig;
|
||||
static pidProfile_t *pidProfile;
|
||||
|
||||
|
|
|
@ -44,18 +44,18 @@
|
|||
#include "drivers/gpio.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "flight/flight.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "rx/rx.h"
|
||||
|
||||
|
||||
#include "io/escservo.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/spektrum.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
@ -63,6 +63,13 @@
|
|||
#include "sensors/gyro.h"
|
||||
#include "sensors/compass.h"
|
||||
#include "sensors/barometer.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "flight/failsafe.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
|
|
|
@ -41,20 +41,16 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "flight/altitudehold.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "sensors/boardalignment.h"
|
||||
|
@ -66,6 +62,13 @@
|
|||
#include "sensors/compass.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "flight/altitudehold.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -25,6 +25,8 @@
|
|||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/atomic.h"
|
||||
#include "common/maths.h"
|
||||
|
||||
#include "drivers/nvic.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
|
@ -45,30 +47,34 @@
|
|||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/inverter.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/display.h"
|
||||
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/sonar.h"
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/compass.h"
|
||||
#include "sensors/acceleration.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "blackbox/blackbox.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "blackbox/blackbox.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -37,7 +37,6 @@
|
|||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/sonar.h"
|
||||
|
@ -46,18 +45,12 @@
|
|||
#include "sensors/barometer.h"
|
||||
#include "sensors/gyro.h"
|
||||
#include "sensors/battery.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/display.h"
|
||||
#include "io/escservo.h"
|
||||
#include "rx/rx.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/rc_curves.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/altitudehold.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/autotune.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
@ -65,10 +58,22 @@
|
|||
#include "io/serial_cli.h"
|
||||
#include "io/serial_msp.h"
|
||||
#include "io/statusindicator.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "blackbox/blackbox.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/flight.h"
|
||||
#include "flight/altitudehold.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/autotune.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
|
||||
#include "config/runtime_config.h"
|
||||
#include "config/config.h"
|
||||
#include "config/config_profile.h"
|
||||
|
|
|
@ -25,8 +25,6 @@
|
|||
#include "drivers/sensor.h"
|
||||
#include "drivers/accgyro.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "io/beeper.h"
|
||||
|
@ -36,6 +34,8 @@
|
|||
|
||||
#include "sensors/acceleration.h"
|
||||
|
||||
int16_t accADC[XYZ_AXIS_COUNT];
|
||||
|
||||
acc_t acc; // acc access functions
|
||||
uint8_t accHardware = ACC_DEFAULT; // which accel chip is used/detected
|
||||
sensor_align_e accAlign = 0;
|
||||
|
@ -71,6 +71,12 @@ bool isOnFirstAccelerationCalibrationCycle(void)
|
|||
return calibratingA == CALIBRATING_ACC_CYCLES;
|
||||
}
|
||||
|
||||
void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims)
|
||||
{
|
||||
rollAndPitchTrims->values.roll = 0;
|
||||
rollAndPitchTrims->values.pitch = 0;
|
||||
}
|
||||
|
||||
void performAcclerationCalibration(rollAndPitchTrims_t *rollAndPitchTrims)
|
||||
{
|
||||
static int32_t a[3];
|
||||
|
@ -92,9 +98,9 @@ void performAcclerationCalibration(rollAndPitchTrims_t *rollAndPitchTrims)
|
|||
|
||||
if (isOnFinalAccelerationCalibrationCycle()) {
|
||||
// Calculate average, shift Z down by acc_1G and store values in EEPROM at end of calibration
|
||||
accelerationTrims->raw[FD_ROLL] = (a[FD_ROLL] + (CALIBRATING_ACC_CYCLES / 2)) / CALIBRATING_ACC_CYCLES;
|
||||
accelerationTrims->raw[FD_PITCH] = (a[FD_PITCH] + (CALIBRATING_ACC_CYCLES / 2)) / CALIBRATING_ACC_CYCLES;
|
||||
accelerationTrims->raw[FD_YAW] = (a[FD_YAW] + (CALIBRATING_ACC_CYCLES / 2)) / CALIBRATING_ACC_CYCLES - acc_1G;
|
||||
accelerationTrims->raw[X] = (a[X] + (CALIBRATING_ACC_CYCLES / 2)) / CALIBRATING_ACC_CYCLES;
|
||||
accelerationTrims->raw[Y] = (a[Y] + (CALIBRATING_ACC_CYCLES / 2)) / CALIBRATING_ACC_CYCLES;
|
||||
accelerationTrims->raw[Z] = (a[Z] + (CALIBRATING_ACC_CYCLES / 2)) / CALIBRATING_ACC_CYCLES - acc_1G;
|
||||
|
||||
resetRollAndPitchTrims(rollAndPitchTrims);
|
||||
|
||||
|
@ -113,9 +119,9 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri
|
|||
|
||||
// Saving old zeropoints before measurement
|
||||
if (InflightcalibratingA == 50) {
|
||||
accZero_saved[FD_ROLL] = accelerationTrims->raw[FD_ROLL];
|
||||
accZero_saved[FD_PITCH] = accelerationTrims->raw[FD_PITCH];
|
||||
accZero_saved[FD_YAW] = accelerationTrims->raw[FD_YAW];
|
||||
accZero_saved[X] = accelerationTrims->raw[X];
|
||||
accZero_saved[Y] = accelerationTrims->raw[Y];
|
||||
accZero_saved[Z] = accelerationTrims->raw[Z];
|
||||
angleTrim_saved.values.roll = rollAndPitchTrims->values.roll;
|
||||
angleTrim_saved.values.pitch = rollAndPitchTrims->values.pitch;
|
||||
}
|
||||
|
@ -136,9 +142,9 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri
|
|||
AccInflightCalibrationMeasurementDone = true;
|
||||
queueConfirmationBeep(5); // beeper to indicating the end of calibration
|
||||
// recover saved values to maintain current flight behaviour until new values are transferred
|
||||
accelerationTrims->raw[FD_ROLL] = accZero_saved[FD_ROLL];
|
||||
accelerationTrims->raw[FD_PITCH] = accZero_saved[FD_PITCH];
|
||||
accelerationTrims->raw[FD_YAW] = accZero_saved[FD_YAW];
|
||||
accelerationTrims->raw[X] = accZero_saved[X];
|
||||
accelerationTrims->raw[Y] = accZero_saved[Y];
|
||||
accelerationTrims->raw[Z] = accZero_saved[Z];
|
||||
rollAndPitchTrims->values.roll = angleTrim_saved.values.roll;
|
||||
rollAndPitchTrims->values.pitch = angleTrim_saved.values.pitch;
|
||||
}
|
||||
|
@ -147,9 +153,9 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri
|
|||
// Calculate average, shift Z down by acc_1G and store values in EEPROM at end of calibration
|
||||
if (AccInflightCalibrationSavetoEEProm) { // the aircraft is landed, disarmed and the combo has been done again
|
||||
AccInflightCalibrationSavetoEEProm = false;
|
||||
accelerationTrims->raw[FD_ROLL] = b[FD_ROLL] / 50;
|
||||
accelerationTrims->raw[FD_PITCH] = b[FD_PITCH] / 50;
|
||||
accelerationTrims->raw[FD_YAW] = b[FD_YAW] / 50 - acc_1G; // for nunchuck 200=1G
|
||||
accelerationTrims->raw[X] = b[X] / 50;
|
||||
accelerationTrims->raw[Y] = b[Y] / 50;
|
||||
accelerationTrims->raw[Z] = b[Z] / 50 - acc_1G; // for nunchuck 200=1G
|
||||
|
||||
resetRollAndPitchTrims(rollAndPitchTrims);
|
||||
|
||||
|
@ -159,9 +165,9 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri
|
|||
|
||||
void applyAccelerationTrims(flightDynamicsTrims_t *accelerationTrims)
|
||||
{
|
||||
accADC[FD_ROLL] -= accelerationTrims->raw[FD_ROLL];
|
||||
accADC[FD_PITCH] -= accelerationTrims->raw[FD_PITCH];
|
||||
accADC[FD_YAW] -= accelerationTrims->raw[FD_YAW];
|
||||
accADC[X] -= accelerationTrims->raw[X];
|
||||
accADC[Y] -= accelerationTrims->raw[Y];
|
||||
accADC[Z] -= accelerationTrims->raw[Z];
|
||||
}
|
||||
|
||||
void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims)
|
||||
|
|
|
@ -36,12 +36,20 @@ extern sensor_align_e accAlign;
|
|||
extern acc_t acc;
|
||||
extern uint16_t acc_1G;
|
||||
|
||||
typedef struct accDeadband_s {
|
||||
uint8_t xy; // set the acc deadband for xy-Axis
|
||||
uint8_t z; // set the acc deadband for z-Axis, this ignores small accelerations
|
||||
} accDeadband_t;
|
||||
extern int16_t accADC[XYZ_AXIS_COUNT];
|
||||
|
||||
typedef struct rollAndPitchTrims_s {
|
||||
int16_t roll;
|
||||
int16_t pitch;
|
||||
} rollAndPitchTrims_t_def;
|
||||
|
||||
typedef union {
|
||||
int16_t raw[2];
|
||||
rollAndPitchTrims_t_def values;
|
||||
} rollAndPitchTrims_t;
|
||||
|
||||
bool isAccelerationCalibrationComplete(void);
|
||||
void accSetCalibrationCycles(uint16_t calibrationCyclesRequired);
|
||||
void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims);
|
||||
void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims);
|
||||
void setAccelerationTrims(flightDynamicsTrims_t *accelerationTrimsToUse);
|
||||
|
|
|
@ -17,6 +17,18 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
|
||||
typedef struct int16_flightDynamicsTrims_s {
|
||||
int16_t roll;
|
||||
int16_t pitch;
|
||||
int16_t yaw;
|
||||
} flightDynamicsTrims_def_t;
|
||||
|
||||
typedef union {
|
||||
int16_t raw[3];
|
||||
flightDynamicsTrims_def_t values;
|
||||
} flightDynamicsTrims_t;
|
||||
|
||||
#define CALIBRATING_GYRO_CYCLES 1000
|
||||
#define CALIBRATING_ACC_CYCLES 400
|
||||
#define CALIBRATING_BARO_CYCLES 200 // 10 seconds init_delay + 200 * 25 ms = 15 seconds before ground pressure settles
|
||||
|
|
|
@ -27,18 +27,16 @@
|
|||
#include "drivers/adc.h"
|
||||
#include "drivers/light_led.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "rx/rx.h"
|
||||
#include "rx/msp.h"
|
||||
|
||||
#include "io/escservo.h"
|
||||
#include "io/rc_controls.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/gimbal.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/ledstrip.h"
|
||||
|
||||
#include "sensors/boardalignment.h"
|
||||
#include "sensors/sensors.h"
|
||||
#include "sensors/battery.h"
|
||||
|
@ -47,6 +45,12 @@
|
|||
#include "sensors/compass.h"
|
||||
#include "sensors/gyro.h"
|
||||
|
||||
#include "flight/flight.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/navigation.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
#include "telemetry/smartport.h"
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue