mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 05:15:25 +03:00
120hz altitude data used in GPS Rescue
Disarm on crash flip recovery or impact while in do nothing mode add blackbox headers for new fields rearrange altitude factors fix ibus uint16 for estimatedVario update GPS altitude at 120hz get GPS derivative from error PT2 filter on GPS derivative remove acceleration element move altitude filtering to position.c calculate altitude derivative in position.c for vario filter vario with PT1 update pg in position and baro field and test tuning from field tests land 3x faster from higher altitude PT2 vario for checking GPS
This commit is contained in:
parent
e1cafc0434
commit
b88e73d137
12 changed files with 261 additions and 251 deletions
|
@ -32,6 +32,8 @@
|
|||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/pid.h"
|
||||
#include "flight/position.h"
|
||||
#include "flight/gps_rescue.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
#include "pg/pg_ids.h"
|
||||
|
@ -46,6 +48,7 @@
|
|||
#include "sensors/rangefinder.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
|
||||
// requestedSensors is not actually used
|
||||
uint8_t requestedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE };
|
||||
uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE, RANGEFINDER_NONE };
|
||||
|
@ -84,6 +87,9 @@ bool sensorsAutodetect(void)
|
|||
baroInit();
|
||||
#endif
|
||||
|
||||
positionInit();
|
||||
gpsRescueInit();
|
||||
|
||||
#ifdef USE_RANGEFINDER
|
||||
rangefinderInit();
|
||||
#endif
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue