1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-24 00:35:34 +03:00

Move 3d_deadband_throttle to rcControlsConfig

This commit is contained in:
Konstantin Sharlaimov (DigitalEntity) 2017-02-01 01:02:19 +10:00
parent 8811a87ca6
commit cc2d7b01de
15 changed files with 27 additions and 29 deletions

View file

@ -630,7 +630,6 @@ static const clivalue_t valueTable[] = {
{ "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, deadband3d_low) }, // FIXME upper limit should match code in the mixer, 1500 currently { "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, deadband3d_low) }, // FIXME upper limit should match code in the mixer, 1500 currently
{ "3d_deadband_high", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, deadband3d_high) }, // FIXME lower limit should match code in the mixer, 1500 currently, { "3d_deadband_high", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, deadband3d_high) }, // FIXME lower limit should match code in the mixer, 1500 currently,
{ "3d_neutral", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, neutral3d) }, { "3d_neutral", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, neutral3d) },
{ "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, deadband3d_throttle) },
#ifdef USE_SERVOS #ifdef USE_SERVOS
// PG_SERVO_CONFIG // PG_SERVO_CONFIG
@ -686,6 +685,7 @@ static const clivalue_t valueTable[] = {
{ "yaw_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, yaw_deadband) }, { "yaw_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, yaw_deadband) },
{ "pos_hold_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 250 }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, pos_hold_deadband) }, { "pos_hold_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 250 }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, pos_hold_deadband) },
{ "alt_hold_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 250 }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, alt_hold_deadband) }, { "alt_hold_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 250 }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, alt_hold_deadband) },
{ "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(rcControlsConfig_t, deadband3d_throttle) },
// PG_PID_PROFILE // PG_PID_PROFILE
// { "default_rate_profile", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, MAX_CONTROL_RATE_PROFILE_COUNT - 1 }, PG_PID_CONFIG, offsetof(pidProfile_t, defaultRateProfileIndex) }, // { "default_rate_profile", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, MAX_CONTROL_RATE_PROFILE_COUNT - 1 }, PG_PID_CONFIG, offsetof(pidProfile_t, defaultRateProfileIndex) },

View file

@ -319,7 +319,7 @@ void processRx(timeUs_t currentTimeUs)
failsafeUpdateState(); failsafeUpdateState();
const throttleStatus_e throttleStatus = calculateThrottleStatus(flight3DConfig()->deadband3d_throttle); const throttleStatus_e throttleStatus = calculateThrottleStatus();
// When armed and motors aren't spinning, do beeps and then disarm // When armed and motors aren't spinning, do beeps and then disarm
// board after delay so users without buzzer won't lose fingers. // board after delay so users without buzzer won't lose fingers.

View file

@ -512,7 +512,7 @@ void init(void)
cliInit(serialConfig()); cliInit(serialConfig());
#endif #endif
failsafeInit(flight3DConfig()->deadband3d_throttle); failsafeInit();
rxInit(); rxInit();

View file

@ -1037,7 +1037,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn
sbufWriteU8(dst, rcControlsConfig()->deadband); sbufWriteU8(dst, rcControlsConfig()->deadband);
sbufWriteU8(dst, rcControlsConfig()->yaw_deadband); sbufWriteU8(dst, rcControlsConfig()->yaw_deadband);
sbufWriteU8(dst, rcControlsConfig()->alt_hold_deadband); sbufWriteU8(dst, rcControlsConfig()->alt_hold_deadband);
sbufWriteU16(dst, flight3DConfig()->deadband3d_throttle); sbufWriteU16(dst, rcControlsConfig()->deadband3d_throttle);
break; break;
case MSP_SENSOR_ALIGNMENT: case MSP_SENSOR_ALIGNMENT:
@ -1515,7 +1515,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
rcControlsConfigMutable()->deadband = sbufReadU8(src); rcControlsConfigMutable()->deadband = sbufReadU8(src);
rcControlsConfigMutable()->yaw_deadband = sbufReadU8(src); rcControlsConfigMutable()->yaw_deadband = sbufReadU8(src);
rcControlsConfigMutable()->alt_hold_deadband = sbufReadU8(src); rcControlsConfigMutable()->alt_hold_deadband = sbufReadU8(src);
flight3DConfigMutable()->deadband3d_throttle = sbufReadU16(src); rcControlsConfigMutable()->deadband3d_throttle = sbufReadU16(src);
break; break;
case MSP_SET_RESET_CURR_PID: case MSP_SET_RESET_CURR_PID:

View file

@ -112,7 +112,7 @@ void taskUpdateBattery(timeUs_t currentTimeUs)
if (ibatTimeSinceLastServiced >= IBATINTERVAL) { if (ibatTimeSinceLastServiced >= IBATINTERVAL) {
ibatLastServiced = currentTimeUs; ibatLastServiced = currentTimeUs;
currentMeterUpdate(ibatTimeSinceLastServiced, flight3DConfig()->deadband3d_throttle); currentMeterUpdate(ibatTimeSinceLastServiced);
} }
} }
} }

View file

@ -78,7 +78,8 @@ PG_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig,
.deadband = 5, .deadband = 5,
.yaw_deadband = 5, .yaw_deadband = 5,
.pos_hold_deadband = 20, .pos_hold_deadband = 20,
.alt_hold_deadband = 50 .alt_hold_deadband = 50,
.deadband3d_throttle = 50
); );
PG_REGISTER_WITH_RESET_TEMPLATE(armingConfig_t, armingConfig, PG_ARMING_CONFIG, 0); PG_REGISTER_WITH_RESET_TEMPLATE(armingConfig_t, armingConfig, PG_ARMING_CONFIG, 0);
@ -108,8 +109,9 @@ bool areSticksInApModePosition(uint16_t ap_mode)
return ABS(rcCommand[ROLL]) < ap_mode && ABS(rcCommand[PITCH]) < ap_mode; return ABS(rcCommand[ROLL]) < ap_mode && ABS(rcCommand[PITCH]) < ap_mode;
} }
throttleStatus_e calculateThrottleStatus(uint16_t deadband3d_throttle) throttleStatus_e calculateThrottleStatus(void)
{ {
const uint16_t deadband3d_throttle = rcControlsConfig()->deadband3d_throttle;
if (feature(FEATURE_3D) && (rcData[THROTTLE] > (rxConfig()->midrc - deadband3d_throttle) && rcData[THROTTLE] < (rxConfig()->midrc + deadband3d_throttle))) if (feature(FEATURE_3D) && (rcData[THROTTLE] > (rxConfig()->midrc - deadband3d_throttle) && rcData[THROTTLE] < (rxConfig()->midrc + deadband3d_throttle)))
return THROTTLE_LOW; return THROTTLE_LOW;
else if (!feature(FEATURE_3D) && (rcData[THROTTLE] < rxConfig()->mincheck)) else if (!feature(FEATURE_3D) && (rcData[THROTTLE] < rxConfig()->mincheck))

View file

@ -143,6 +143,7 @@ typedef struct rcControlsConfig_s {
uint8_t yaw_deadband; // introduce a deadband around the stick center for yaw axis. Must be greater than zero. uint8_t yaw_deadband; // introduce a deadband around the stick center for yaw axis. Must be greater than zero.
uint8_t pos_hold_deadband; // Adds ability to adjust the Hold-position when moving the sticks (assisted mode) uint8_t pos_hold_deadband; // Adds ability to adjust the Hold-position when moving the sticks (assisted mode)
uint8_t alt_hold_deadband; // Defines the neutral zone of throttle stick during altitude hold uint8_t alt_hold_deadband; // Defines the neutral zone of throttle stick during altitude hold
uint16_t deadband3d_throttle; // default throttle deadband from MIDRC
} rcControlsConfig_t; } rcControlsConfig_t;
PG_DECLARE(rcControlsConfig_t, rcControlsConfig); PG_DECLARE(rcControlsConfig_t, rcControlsConfig);
@ -158,7 +159,7 @@ PG_DECLARE(armingConfig_t, armingConfig);
bool areUsingSticksToArm(void); bool areUsingSticksToArm(void);
bool areSticksInApModePosition(uint16_t ap_mode); bool areSticksInApModePosition(uint16_t ap_mode);
throttleStatus_e calculateThrottleStatus(uint16_t deadband3d_throttle); throttleStatus_e calculateThrottleStatus(void);
rollPitchStatus_e calculateRollPitchCenterStatus(void); rollPitchStatus_e calculateRollPitchCenterStatus(void);
void processRcStickPositions(throttleStatus_e throttleStatus, bool disarm_kill_switch, bool fixed_wing_auto_arm); void processRcStickPositions(throttleStatus_e throttleStatus, bool disarm_kill_switch, bool fixed_wing_auto_arm);

View file

@ -60,8 +60,6 @@
static failsafeState_t failsafeState; static failsafeState_t failsafeState;
static uint16_t deadband3dThrottle; // default throttle deadband from MIDRC
PG_REGISTER_WITH_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, PG_FAILSAFE_CONFIG, 0); PG_REGISTER_WITH_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, PG_FAILSAFE_CONFIG, 0);
PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig,
@ -148,9 +146,8 @@ void failsafeReset(void)
failsafeState.rxLinkState = FAILSAFE_RXLINK_DOWN; failsafeState.rxLinkState = FAILSAFE_RXLINK_DOWN;
} }
void failsafeInit(uint16_t deadband3d_throttle) void failsafeInit(void)
{ {
deadband3dThrottle = deadband3d_throttle;
failsafeState.events = 0; failsafeState.events = 0;
failsafeState.monitoring = false; failsafeState.monitoring = false;
@ -332,7 +329,7 @@ void failsafeUpdateState(void)
case FAILSAFE_IDLE: case FAILSAFE_IDLE:
if (armed) { if (armed) {
// Track throttle command below minimum time // Track throttle command below minimum time
if (THROTTLE_HIGH == calculateThrottleStatus(deadband3dThrottle)) { if (THROTTLE_HIGH == calculateThrottleStatus()) {
failsafeState.throttleLowPeriod = millis() + failsafeConfig()->failsafe_throttle_low_delay * MILLIS_PER_TENTH_SECOND; failsafeState.throttleLowPeriod = millis() + failsafeConfig()->failsafe_throttle_low_delay * MILLIS_PER_TENTH_SECOND;
} }
// Kill switch logic (must be independent of receivingRxData to skip PERIOD_RXDATA_FAILURE delay before disarming) // Kill switch logic (must be independent of receivingRxData to skip PERIOD_RXDATA_FAILURE delay before disarming)

View file

@ -95,7 +95,7 @@ typedef struct failsafeState_s {
int16_t lastGoodRcCommand[4]; int16_t lastGoodRcCommand[4];
} failsafeState_t; } failsafeState_t;
void failsafeInit(uint16_t deadband3d_throttle); void failsafeInit(void);
void failsafeReset(void); void failsafeReset(void);
void failsafeStartMonitoring(void); void failsafeStartMonitoring(void);

View file

@ -68,8 +68,7 @@ PG_REGISTER_WITH_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig, PG_MOTOR_3D_CO
PG_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig, PG_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig,
.deadband3d_low = 1406, .deadband3d_low = 1406,
.deadband3d_high = 1514, .deadband3d_high = 1514,
.neutral3d = 1460, .neutral3d = 1460
.deadband3d_throttle = 50
); );
@ -482,15 +481,15 @@ void mixTable(void)
if (feature(FEATURE_3D)) { if (feature(FEATURE_3D)) {
if (!ARMING_FLAG(ARMED)) throttlePrevious = rxConfig()->midrc; // When disarmed set to mid_rc. It always results in positive direction after arming. if (!ARMING_FLAG(ARMED)) throttlePrevious = rxConfig()->midrc; // When disarmed set to mid_rc. It always results in positive direction after arming.
if ((rcCommand[THROTTLE] <= (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle))) { // Out of band handling if ((rcCommand[THROTTLE] <= (rxConfig()->midrc - rcControlsConfig()->deadband3d_throttle))) { // Out of band handling
throttleMax = flight3DConfig()->deadband3d_low; throttleMax = flight3DConfig()->deadband3d_low;
throttleMin = motorConfig()->minthrottle; throttleMin = motorConfig()->minthrottle;
throttlePrevious = throttleCommand = rcCommand[THROTTLE]; throttlePrevious = throttleCommand = rcCommand[THROTTLE];
} else if (rcCommand[THROTTLE] >= (rxConfig()->midrc + flight3DConfig()->deadband3d_throttle)) { // Positive handling } else if (rcCommand[THROTTLE] >= (rxConfig()->midrc + rcControlsConfig()->deadband3d_throttle)) { // Positive handling
throttleMax = motorConfig()->maxthrottle; throttleMax = motorConfig()->maxthrottle;
throttleMin = flight3DConfig()->deadband3d_high; throttleMin = flight3DConfig()->deadband3d_high;
throttlePrevious = throttleCommand = rcCommand[THROTTLE]; throttlePrevious = throttleCommand = rcCommand[THROTTLE];
} else if ((throttlePrevious <= (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle))) { // Deadband handling from negative to positive } else if ((throttlePrevious <= (rxConfig()->midrc - rcControlsConfig()->deadband3d_throttle))) { // Deadband handling from negative to positive
throttleCommand = throttleMax = flight3DConfig()->deadband3d_low; throttleCommand = throttleMax = flight3DConfig()->deadband3d_low;
throttleMin = motorConfig()->minthrottle; throttleMin = motorConfig()->minthrottle;
} else { // Deadband handling from positive to negative } else { // Deadband handling from positive to negative
@ -534,7 +533,7 @@ void mixTable(void)
if (isFailsafeActive) { if (isFailsafeActive) {
motor[i] = constrain(motor[i], motorConfig()->mincommand, motorConfig()->maxthrottle); motor[i] = constrain(motor[i], motorConfig()->mincommand, motorConfig()->maxthrottle);
} else if (feature(FEATURE_3D)) { } else if (feature(FEATURE_3D)) {
if (throttlePrevious <= (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle)) { if (throttlePrevious <= (rxConfig()->midrc - rcControlsConfig()->deadband3d_throttle)) {
motor[i] = constrain(motor[i], motorConfig()->minthrottle, flight3DConfig()->deadband3d_low); motor[i] = constrain(motor[i], motorConfig()->minthrottle, flight3DConfig()->deadband3d_low);
} else { } else {
motor[i] = constrain(motor[i], flight3DConfig()->deadband3d_high, motorConfig()->maxthrottle); motor[i] = constrain(motor[i], flight3DConfig()->deadband3d_high, motorConfig()->maxthrottle);

View file

@ -98,7 +98,6 @@ typedef struct flight3DConfig_s {
uint16_t deadband3d_low; // min 3d value uint16_t deadband3d_low; // min 3d value
uint16_t deadband3d_high; // max 3d value uint16_t deadband3d_high; // max 3d value
uint16_t neutral3d; // center 3d value uint16_t neutral3d; // center 3d value
uint16_t deadband3d_throttle; // default throttle deadband from MIDRC
} flight3DConfig_t; } flight3DConfig_t;
PG_DECLARE(flight3DConfig_t, flight3DConfig); PG_DECLARE(flight3DConfig_t, flight3DConfig);

View file

@ -149,7 +149,7 @@ bool adjustMulticopterAltitudeFromRCInput(void)
void setupMulticopterAltitudeController(void) void setupMulticopterAltitudeController(void)
{ {
const throttleStatus_e throttleStatus = calculateThrottleStatus(flight3DConfig()->deadband3d_throttle); const throttleStatus_e throttleStatus = calculateThrottleStatus();
if (navConfig()->general.flags.use_thr_mid_for_althold) { if (navConfig()->general.flags.use_thr_mid_for_althold) {
altHoldThrottleRCZero = rcLookupThrottleMid(); altHoldThrottleRCZero = rcLookupThrottleMid();

View file

@ -185,7 +185,7 @@ int32_t currentSensorToCentiamps(uint16_t src)
return (millivolts * 1000) / (int32_t)batteryConfig()->currentMeterScale; // current in 0.01A steps return (millivolts * 1000) / (int32_t)batteryConfig()->currentMeterScale; // current in 0.01A steps
} }
void currentMeterUpdate(int32_t lastUpdateAt, uint16_t deadband3d_throttle) void currentMeterUpdate(int32_t lastUpdateAt)
{ {
static int32_t amperageRaw = 0; static int32_t amperageRaw = 0;
static int64_t mAhdrawnRaw = 0; static int64_t mAhdrawnRaw = 0;
@ -201,7 +201,7 @@ void currentMeterUpdate(int32_t lastUpdateAt, uint16_t deadband3d_throttle)
case CURRENT_SENSOR_VIRTUAL: case CURRENT_SENSOR_VIRTUAL:
amperage = (int32_t)batteryConfig()->currentMeterOffset; amperage = (int32_t)batteryConfig()->currentMeterOffset;
if (ARMING_FLAG(ARMED)) { if (ARMING_FLAG(ARMED)) {
throttleStatus_e throttleStatus = calculateThrottleStatus(deadband3d_throttle); throttleStatus_e throttleStatus = calculateThrottleStatus();
if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP)) if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP))
throttleOffset = 0; throttleOffset = 0;
throttleFactor = throttleOffset + (throttleOffset * throttleOffset / 50); throttleFactor = throttleOffset + (throttleOffset * throttleOffset / 50);

View file

@ -74,7 +74,7 @@ batteryState_e getBatteryState(void);
void batteryUpdate(uint32_t vbatTimeDelta); void batteryUpdate(uint32_t vbatTimeDelta);
void batteryInit(void); void batteryInit(void);
void currentMeterUpdate(int32_t lastUpdateAt, uint16_t deadband3d_throttle); void currentMeterUpdate(int32_t lastUpdateAt);
int32_t currentMeterToCentiamps(uint16_t src); int32_t currentMeterToCentiamps(uint16_t src);
uint8_t calculateBatteryPercentage(void); uint8_t calculateBatteryPercentage(void);

View file

@ -188,12 +188,12 @@ static void sendGpsAltitude(void)
} }
#endif #endif
static void sendThrottleOrBatterySizeAsRpm(uint16_t deadband3d_throttle) static void sendThrottleOrBatterySizeAsRpm(void)
{ {
uint16_t throttleForRPM = rcCommand[THROTTLE] / BLADE_NUMBER_DIVIDER; uint16_t throttleForRPM = rcCommand[THROTTLE] / BLADE_NUMBER_DIVIDER;
sendDataHead(ID_RPM); sendDataHead(ID_RPM);
if (ARMING_FLAG(ARMED)) { if (ARMING_FLAG(ARMED)) {
const throttleStatus_e throttleStatus = calculateThrottleStatus(deadband3d_throttle); const throttleStatus_e throttleStatus = calculateThrottleStatus();
if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP)) if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP))
throttleForRPM = 0; throttleForRPM = 0;
serialize16(throttleForRPM); serialize16(throttleForRPM);
@ -519,7 +519,7 @@ void handleFrSkyTelemetry(void)
if ((cycleNum % 8) == 0) { // Sent every 1s if ((cycleNum % 8) == 0) { // Sent every 1s
sendTemperature1(); sendTemperature1();
sendThrottleOrBatterySizeAsRpm(flight3DConfig()->deadband3d_throttle); sendThrottleOrBatterySizeAsRpm();
if (feature(FEATURE_VBAT)) { if (feature(FEATURE_VBAT)) {
sendVoltage(); sendVoltage();