1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-17 21:35:44 +03:00

Improved rx, failsafe and pid structure alignments

This commit is contained in:
Martin Budden 2017-07-29 17:35:43 +01:00
parent b1ec3d04f2
commit d180266f7d
6 changed files with 10 additions and 11 deletions

View file

@ -55,13 +55,13 @@
static failsafeState_t failsafeState;
PG_REGISTER_WITH_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, PG_FAILSAFE_CONFIG, 1);
PG_REGISTER_WITH_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, PG_FAILSAFE_CONFIG, 2);
PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig,
.failsafe_delay = 10, // 1sec
.failsafe_off_delay = 10, // 1sec
.failsafe_throttle = 1000, // default throttle off.
.failsafe_throttle_low_delay = 100, // default throttle low delay for "just disarm" on failsafe condition
.failsafe_delay = 10, // 1sec
.failsafe_off_delay = 10, // 1sec
.failsafe_kill_switch = 0, // default failsafe switch action is identical to rc link loss
.failsafe_procedure = FAILSAFE_PROCEDURE_DROP_IT // default full failsafe procedure is 0: auto-landing
);

View file

@ -30,10 +30,10 @@
typedef struct failsafeConfig_s {
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_throttle_low_delay; // Time throttle stick must have been below 'min_check' to "JustDisarm" instead of "full failsafe procedure".
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)
uint8_t failsafe_kill_switch; // failsafe switch action is 0: identical to rc link loss, 1: disarms instantly
uint8_t failsafe_procedure; // selected full failsafe procedure is 0: auto-landing, 1: Drop it
} failsafeConfig_t;

View file

@ -69,7 +69,7 @@ PG_RESET_TEMPLATE(pidConfig_t, pidConfig,
.pid_process_denom = PID_PROCESS_DENOM_DEFAULT
);
PG_REGISTER_ARRAY_WITH_RESET_FN(pidProfile_t, MAX_PROFILE_COUNT, pidProfiles, PG_PID_PROFILE, 0);
PG_REGISTER_ARRAY_WITH_RESET_FN(pidProfile_t, MAX_PROFILE_COUNT, pidProfiles, PG_PID_PROFILE, 1);
void resetPidProfile(pidProfile_t *pidProfile)
{

View file

@ -82,7 +82,6 @@ typedef struct pidProfile_s {
uint8_t itermWindupPointPercent; // Experimental ITerm windup threshold, percent motor saturation
uint16_t pidSumLimit;
uint16_t pidSumLimitYaw;
uint8_t dterm_average_count; // Configurable delta count for dterm
uint8_t vbatPidCompensation; // Scale PIDsum to battery voltage
uint8_t pidAtMinThrottle; // Disable/Enable pids on zero throttle. Normally even without airmode P and D would be active.
uint8_t levelAngleLimit; // Max angle in degrees in level mode

View file

@ -117,7 +117,7 @@ static uint8_t rcSampleIndex = 0;
#define BINDPLUG_PIN NONE
#endif
PG_REGISTER_WITH_RESET_FN(rxConfig_t, rxConfig, PG_RX_CONFIG, 0);
PG_REGISTER_WITH_RESET_FN(rxConfig_t, rxConfig, PG_RX_CONFIG, 1);
void pgResetFn_rxConfig(rxConfig_t *rxConfig)
{
RESET_CONFIG_2(rxConfig_t, rxConfig,
@ -141,8 +141,8 @@ void pgResetFn_rxConfig(rxConfig_t *rxConfig)
.rcInterpolationChannels = 0,
.rcInterpolationInterval = 19,
.fpvCamAngleDegrees = 0,
.max_aux_channel = DEFAULT_AUX_CHANNEL_COUNT,
.airModeActivateThreshold = 1350
.airModeActivateThreshold = 1350,
.max_aux_channel = DEFAULT_AUX_CHANNEL_COUNT
);
#ifdef RX_CHANNELS_TAER

View file

@ -136,11 +136,11 @@ typedef struct rxConfig_s {
uint8_t rcInterpolationChannels;
uint8_t rcInterpolationInterval;
uint8_t fpvCamAngleDegrees; // Camera angle to be scaled into rc commands
uint8_t max_aux_channel;
uint16_t airModeActivateThreshold; // Throttle setpoint where airmode gets activated
uint16_t rx_min_usec;
uint16_t rx_max_usec;
uint8_t max_aux_channel;
} rxConfig_t;
PG_DECLARE(rxConfig_t, rxConfig);