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

Detach midrc (input) from servo center (output).

This fixes incorrect servo center position when midrc was not 1500.
Most likely only experienced by futaba plane or servo/tilt users.
This commit is contained in:
Dominic Clifton 2015-01-27 22:55:41 +01:00
parent f4ec9a2c65
commit a2b232e805
6 changed files with 10 additions and 5 deletions

View file

@ -197,6 +197,7 @@ void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig)
escAndServoConfig->minthrottle = 1150;
escAndServoConfig->maxthrottle = 1850;
escAndServoConfig->mincommand = 1000;
escAndServoConfig->servoCenterPulse = 1500;
}
void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)

View file

@ -473,14 +473,14 @@ static void airplaneMixer(void)
int16_t lFlap = determineServoMiddleOrForwardFromChannel(2);
lFlap = constrain(lFlap, servoConf[2].min, servoConf[2].max);
lFlap = rxConfig->midrc - lFlap;
lFlap = escAndServoConfig->servoCenterPulse - lFlap;
if (slow_LFlaps < lFlap)
slow_LFlaps += airplaneConfig->flaps_speed;
else if (slow_LFlaps > lFlap)
slow_LFlaps -= airplaneConfig->flaps_speed;
servo[2] = ((int32_t)servoConf[2].rate * slow_LFlaps) / 100L;
servo[2] += rxConfig->midrc;
servo[2] += escAndServoConfig->servoCenterPulse;
}
if (FLIGHT_MODE(PASSTHRU_MODE)) { // Direct passthru from RX

View file

@ -18,7 +18,10 @@
#pragma once
typedef struct escAndServoConfig_s {
// PWM values, in milliseconds, common range is 1000-2000 (1 to 2ms)
uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed.
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
uint16_t servoCenterPulse; // This is the value for servos when they should be in the middle. e.g. 1500.
} escAndServoConfig_t;

View file

@ -226,6 +226,7 @@ const clivalue_t valueTable[] = {
{ "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
{ "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
{ "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, PWM_RANGE_ZERO, PWM_RANGE_MAX },
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, PWM_RANGE_ZERO, PWM_RANGE_MAX },
{ "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_low, PWM_RANGE_ZERO, PWM_RANGE_MAX }, // FIXME upper limit should match code in the mixer, 1500 currently
{ "3d_deadband_high", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_high, PWM_RANGE_ZERO, PWM_RANGE_MAX }, // FIXME lower limit should match code in the mixer, 1500 currently,

View file

@ -305,7 +305,7 @@ void init(void)
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
if (pwm_params.motorPwmRate > 500)
pwm_params.idlePulse = 0; // brushed motors
pwm_params.servoCenterPulse = masterConfig.rxConfig.midrc;
pwm_params.servoCenterPulse = masterConfig.escAndServoConfig.servoCenterPulse;
pwmRxInit(masterConfig.inputFilteringMode);

View file

@ -68,11 +68,11 @@ typedef struct rxConfig_s {
uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order
uint8_t serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first.
uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers
uint8_t rssi_channel;
uint8_t rssi_scale;
uint16_t midrc; // Some radios have not a neutral point centered on 1500. can be changed here
uint16_t mincheck; // minimum rc end
uint16_t maxcheck; // maximum rc end
uint8_t rssi_channel;
uint8_t rssi_scale;
} rxConfig_t;
#define REMAPPABLE_CHANNEL_COUNT (sizeof(((rxConfig_t *)0)->rcmap) / sizeof(((rxConfig_t *)0)->rcmap[0]))