1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 16:55:36 +03:00

tidy up after merge

This commit is contained in:
ctzsnooze 2024-10-17 11:49:32 +11:00
parent ce72f16a62
commit 7c85c9a7e7
7 changed files with 4 additions and 10 deletions

View file

@ -63,7 +63,6 @@
#include "fc/runtime_config.h"
#include "flight/alt_hold.h"
#include "flight/pos_hold.h"
#include "flight/autopilot.h"
#include "flight/failsafe.h"
#include "flight/gps_rescue.h"

View file

@ -104,7 +104,6 @@ bool cliMode = false;
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "flight/autopilot.h"
#include "flight/failsafe.h"
#include "flight/imu.h"
#include "flight/mixer.h"

View file

@ -53,13 +53,12 @@
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "flight/alt_hold.h"
#include "flight/gps_rescue.h"
#include "flight/imu.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/position.h"
#include "flight/autopilot.h"
#include "flight/alt_hold.h"
#include "flight/pos_hold.h"
#include "io/asyncfatfs/asyncfatfs.h"

View file

@ -45,11 +45,11 @@
#define POSITION_J_SCALE 0.0008f
static pidCoefficient_t altitudePidCoeffs;
static pidCoefficient_t positionPidCoeffs;
static float altitudeI = 0.0f;
static float throttleOut = 0.0f;
static pidCoefficient_t positionPidCoeffs;
typedef struct {
uint32_t distanceCm;
uint32_t previousDistanceCm;
@ -78,7 +78,6 @@ static posHoldState posHold = {
static gpsLocation_t currentTargetLocation = {0, 0, 0};
float posHoldAngle[ANGLE_INDEX_COUNT];
static pt1Filter_t velocityPitchLpf;
static pt1Filter_t accelerationPitchLpf;
static pt1Filter_t velocityRollLpf;

View file

@ -31,5 +31,4 @@ void altitudeControl(float targetAltitudeCm, float taskIntervalS, float vertical
bool positionControl(float deadband);
bool isBelowLandingAltitude(void);
const pidCoefficient_t *getAltitudePidCoeffs(void);
float getAutopilotThrottle(void);

View file

@ -46,7 +46,6 @@
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "flight/alt_hold.h"
#include "flight/autopilot.h"
#include "flight/gps_rescue.h"
#include "flight/imu.h"

View file

@ -21,8 +21,8 @@
#include "math.h"
#include "build/debug.h"
#include "common/maths.h"
#include "config/config.h"
#include "fc/runtime_config.h"
#include "fc/rc.h"