mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 06:15:16 +03:00
Fix servo middle/channel forwarding variable re-use. Adds a new
capability flag which is returned by MSP IDENT (CAP_CHANNEL_FORWARDING). Adds two new MSP commands that are specifically for configuring channel forwarding (MSP_CHANNEL_FORWARDING/MSP_SET_CHANNEL_FORWARDING). Servo 'middle' and 'forward from channel' are now stored independently, as they probably should always have been.
This commit is contained in:
parent
43258c045d
commit
b8e7c2d14f
5 changed files with 52 additions and 24 deletions
|
@ -39,7 +39,7 @@ void setPIDController(int type); // FIXME PID code needs to be in flight_pid.c/h
|
|||
master_t mcfg; // master config struct with data independent from profiles
|
||||
config_t cfg; // profile config struct
|
||||
|
||||
static const uint8_t EEPROM_CONF_VERSION = 62;
|
||||
static const uint8_t EEPROM_CONF_VERSION = 63;
|
||||
static void resetConf(void);
|
||||
|
||||
static uint8_t validEEPROM(void)
|
||||
|
@ -291,10 +291,11 @@ static void resetConf(void)
|
|||
|
||||
// servos
|
||||
for (i = 0; i < 8; i++) {
|
||||
cfg.servoConf[i].min = 1020;
|
||||
cfg.servoConf[i].max = 2000;
|
||||
cfg.servoConf[i].middle = 1500;
|
||||
cfg.servoConf[i].min = DEFAULT_SERVO_MIN;
|
||||
cfg.servoConf[i].max = DEFAULT_SERVO_MAX;
|
||||
cfg.servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
|
||||
cfg.servoConf[i].rate = servoRates[i];
|
||||
cfg.servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
|
||||
}
|
||||
|
||||
cfg.yaw_direction = 1;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue