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

RPY to mid-stick and T to lowest (or mid for 3D).

On bad (out-of-range) pulses; ROLL, PITCH, YAW will go to `mid_rc` and
THROTTLE will go to `rx_min_usec` (to `mid_rc` for 3D mode). So these
channels will no longer be set by the user directly.
Fallback values for the aux switches (0 .. max) can be set with this
version. Since these switches may trigger all kind of things, the user
needs control over them in case of a RX failsafe event.

A single flight control channel failure (first 4) when using parallel
PWM is interpreted as a failure for all flight control channels (first
4), since the craft may be uncontrollable when one channel is down. (+4
squashed commit)

Squashed commit:

[dbfea9e] Apply fallback values also when serial_rx init failed and/or
RX
disconnected and/or no signal received.

[b5a2ecd] Added get/set MSP commands for RXFAIL config

Bumped API minor version up.

[c0e31ce] minor change for coding standard

[322705f] Added programmable RX channel defaults on rx lost Update #2
This commit is contained in:
ProDrone 2015-06-04 23:31:04 +02:00
parent c282cf4ea7
commit 08b376f2a5
5 changed files with 107 additions and 4 deletions

View file

@ -227,6 +227,10 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER;
#define MSP_FAILSAFE_CONFIG 75 //out message Returns FC Fail-Safe settings
#define MSP_SET_FAILSAFE_CONFIG 76 //in message Sets FC Fail-Safe settings
#define MSP_RXFAIL_CONFIG 77 //out message Returns RXFAIL settings
#define MSP_SET_RXFAIL_CONFIG 78 //in message Sets RXFAIL settings
//
// Baseflight MSP commands (if enabled they exist in Cleanflight)
//
@ -1159,6 +1163,13 @@ static bool processOutCommand(uint8_t cmdMSP)
serialize16(masterConfig.failsafeConfig.failsafe_throttle);
break;
case MSP_RXFAIL_CONFIG:
headSerialReply(2 * (rxRuntimeConfig.channelCount-4));
for (i = 4; i < rxRuntimeConfig.channelCount; i++) {
serialize16(RXFAIL_STEP_TO_CHANNEL_VALUE(masterConfig.rxConfig.rx_fail_usec_steps[i-4]));
}
break;
case MSP_RSSI_CONFIG:
headSerialReply(1);
serialize8(masterConfig.rxConfig.rssi_channel);
@ -1584,6 +1595,18 @@ static bool processInCommand(void)
masterConfig.failsafeConfig.failsafe_throttle = read16();
break;
case MSP_SET_RXFAIL_CONFIG:
{
uint8_t channelCount = currentPort->dataSize / sizeof(uint16_t);
if (channelCount > MAX_SUPPORTED_RC_CHANNEL_COUNT-4) {
headSerialError(0);
} else {
for (i = 4; i < channelCount; i++)
masterConfig.rxConfig.rx_fail_usec_steps[i-4] = CHANNEL_VALUE_TO_RXFAIL_STEP(read16());
}
}
break;
case MSP_SET_RSSI_CONFIG:
masterConfig.rxConfig.rssi_channel = read8();
break;