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

beginnings of cli editing support by cehteh; (still buggy)

added and began work on integrating failsafe_detect_threshold
got rid of acc_lpf_for_velocity since that seemed no longer used.


git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@317 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop@gmail.com 2013-05-09 12:26:11 +00:00
parent 3f8fc1b509
commit b6fc652b20
8 changed files with 103 additions and 25 deletions

View file

@ -163,7 +163,6 @@ typedef struct config_t {
// sensor-related stuff
uint8_t acc_lpf_factor; // Set the Low Pass Filter factor for ACC. Increasing this value would reduce ACC noise (visible in GUI), but would increase ACC lag time. Zero = no filter
uint8_t acc_lpf_for_velocity; // ACC lowpass for AccZ height hold
uint8_t accz_deadband; // ??
uint8_t baro_tab_size; // size of baro filter array
float baro_noise_lpf; // additional LPF to reduce baro noise
@ -181,6 +180,7 @@ typedef struct config_t {
uint8_t failsafe_delay; // Guard time for failsafe activation after signal lost. 1 step = 0.1sec - 1sec in example (10)
uint8_t failsafe_off_delay; // Time for Landing before motors stop in 0.1sec. 1 step = 0.1sec - 20sec in example (200)
uint16_t failsafe_throttle; // Throttle level used for landing - specify value between 1000..2000 (pwm pulse width for slightly below hover). center throttle = 1500.
uint16_t failsafe_detect_threshold; // Update controls channel only if pulse is above failsafe_detect_threshold. below this trigger failsafe.
// mixer-related configuration
int8_t yaw_direction;