mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-18 22:05:17 +03:00
Merge branch 'rc-calibration' of
https://github.com/digitalentity/cleanflight into digitalentity-rc-calibration Conflicts: docs/Rx.md src/main/io/serial_cli.c src/main/rx/rx.c src/main/rx/rx.h
This commit is contained in:
commit
27f8223de7
10 changed files with 300 additions and 5 deletions
|
@ -92,6 +92,7 @@ Re-apply any new defaults as desired.
|
||||||
| `play_sound` | index, or none for next |
|
| `play_sound` | index, or none for next |
|
||||||
| `profile` | index (0 to 2) |
|
| `profile` | index (0 to 2) |
|
||||||
| `rateprofile` | index (0 to 2) |
|
| `rateprofile` | index (0 to 2) |
|
||||||
|
| `rccal` | Set R/C channel calibration (stick end points) |
|
||||||
| `save` | save and reboot |
|
| `save` | save and reboot |
|
||||||
| `set` | name=value or blank or * for list |
|
| `set` | name=value or blank or * for list |
|
||||||
| `status` | show system status |
|
| `status` | show system status |
|
||||||
|
|
35
docs/Rx.md
35
docs/Rx.md
|
@ -206,7 +206,7 @@ Use the `input_filtering_mode` CLI setting to select a mode.
|
||||||
| 0 | Disabled |
|
| 0 | Disabled |
|
||||||
| 1 | Enabled |
|
| 1 | Enabled |
|
||||||
|
|
||||||
## Receiver configuration
|
## Receiver configuration.
|
||||||
|
|
||||||
### FrSky D4R-II
|
### FrSky D4R-II
|
||||||
|
|
||||||
|
@ -216,3 +216,36 @@ Set the RX for 'No Pulses'. Turn OFF TX and RX, Turn ON RX. Press and release
|
||||||
|
|
||||||
Set failsafe on channels 1-4 set to OFF in the receiver settings (via transmitter menu).
|
Set failsafe on channels 1-4 set to OFF in the receiver settings (via transmitter menu).
|
||||||
|
|
||||||
|
|
||||||
|
## Receiver Calibration.
|
||||||
|
|
||||||
|
If you have a transmitter/receiver, that output a non-standard pulse range (i.e. 1070-1930 as some Spektrum receivers)
|
||||||
|
you could use rc calibration to map actual range of your transmitter to 1000-2000 as expected by Cleanflight.
|
||||||
|
|
||||||
|
To do this you should figure out what range your transmitter outputs and feed these values to rc calibration control.
|
||||||
|
You can do this in a few simple steps:
|
||||||
|
|
||||||
|
If you have used rc calibration previously you should reset it to prevent it from altering rc input. Do so
|
||||||
|
by entering the following commands in CLI:
|
||||||
|
```
|
||||||
|
rccal 0 1000 2000
|
||||||
|
rccal 1 1000 2000
|
||||||
|
rccal 2 1000 2000
|
||||||
|
rccal 3 1000 2000
|
||||||
|
save
|
||||||
|
```
|
||||||
|
|
||||||
|
Now reboot your FC, connect the configurator, go to the `Receiver` tab move sticks on your transmitter and note min and
|
||||||
|
max values of first 4 channels. Take caution as you can accidentally arm your craft. Best way is to move one channel at
|
||||||
|
a time.
|
||||||
|
|
||||||
|
Go to CLI and set the min and max values with the following command:
|
||||||
|
```
|
||||||
|
rccal <channel_number> <min> <max>
|
||||||
|
```
|
||||||
|
|
||||||
|
For example, if you got 1070-1930 range for roll channel. Roll is `channel 0` so you should type `rccal 0 1070 1930` in
|
||||||
|
the CLI. Be sure to enter the `save` command to save the settings.
|
||||||
|
|
||||||
|
Use sub-trim on your transmitter to set the middle point of pitch, roll, yaw and throttle.
|
||||||
|
|
||||||
|
|
|
@ -414,6 +414,12 @@ static void resetConf(void)
|
||||||
masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
|
masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
|
||||||
masterConfig.rxConfig.rssi_ppm_invert = 0;
|
masterConfig.rxConfig.rssi_ppm_invert = 0;
|
||||||
|
|
||||||
|
// set default calibration to full range and 1:1 mapping
|
||||||
|
for (i = 0; i < MAX_CALIBRATED_RX_CHANNELS; i++) {
|
||||||
|
masterConfig.rxConfig.calibration[i].minrc = PWM_RANGE_MIN;
|
||||||
|
masterConfig.rxConfig.calibration[i].maxrc = PWM_RANGE_MAX;
|
||||||
|
}
|
||||||
|
|
||||||
masterConfig.inputFilteringMode = INPUT_FILTERING_DISABLED;
|
masterConfig.inputFilteringMode = INPUT_FILTERING_DISABLED;
|
||||||
|
|
||||||
masterConfig.retarded_arm = 0;
|
masterConfig.retarded_arm = 0;
|
||||||
|
|
|
@ -421,4 +421,3 @@ void evaluateOtherData(serialPort_t *serialPort, uint8_t receivedChar)
|
||||||
systemResetToBootloader();
|
systemResetToBootloader();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -117,6 +117,7 @@ static void cliSet(char *cmdline);
|
||||||
static void cliGet(char *cmdline);
|
static void cliGet(char *cmdline);
|
||||||
static void cliStatus(char *cmdline);
|
static void cliStatus(char *cmdline);
|
||||||
static void cliVersion(char *cmdline);
|
static void cliVersion(char *cmdline);
|
||||||
|
static void cliRxCalibration(char *cmdline);
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
static void cliGpsPassthrough(char *cmdline);
|
static void cliGpsPassthrough(char *cmdline);
|
||||||
|
@ -258,6 +259,7 @@ const clicmd_t cmdTable[] = {
|
||||||
CLI_COMMAND_DEF("rateprofile", "change rate profile",
|
CLI_COMMAND_DEF("rateprofile", "change rate profile",
|
||||||
"[<index>]", cliRateProfile),
|
"[<index>]", cliRateProfile),
|
||||||
CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
|
CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
|
||||||
|
CLI_COMMAND_DEF("rxcal", "rc calibration", NULL, cliRxCalibration),
|
||||||
CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
|
CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
|
||||||
CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
|
CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
|
@ -927,6 +929,46 @@ static void cliMotorMix(char *cmdline)
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static void cliRxCalibration(char *cmdline)
|
||||||
|
{
|
||||||
|
int i, check = 0;
|
||||||
|
char *ptr;
|
||||||
|
|
||||||
|
if (isEmpty(cmdline)) {
|
||||||
|
for (i = 0; i < MAX_CALIBRATED_RX_CHANNELS; i++) {
|
||||||
|
printf("rccal %u %u %u\r\n", i, masterConfig.rxConfig.calibration[i].minrc, masterConfig.rxConfig.calibration[i].maxrc);
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
ptr = cmdline;
|
||||||
|
i = atoi(ptr);
|
||||||
|
if (i >= 0 && i < MAX_CALIBRATED_RX_CHANNELS) {
|
||||||
|
int minrc, maxrc;
|
||||||
|
ptr = strchr(ptr, ' ');
|
||||||
|
if (ptr) {
|
||||||
|
minrc = atoi(++ptr);
|
||||||
|
check++;
|
||||||
|
}
|
||||||
|
ptr = strchr(ptr, ' ');
|
||||||
|
if (ptr) {
|
||||||
|
maxrc = atoi(++ptr);
|
||||||
|
check++;
|
||||||
|
}
|
||||||
|
if (check != 2) {
|
||||||
|
printf("Wrong number of arguments, needs idx min max\r\n");
|
||||||
|
}
|
||||||
|
else if (minrc < 750 || minrc > 2250 || maxrc < 750 || maxrc > 2250 || minrc >= maxrc) {
|
||||||
|
printf("Parameters error. Should be: 750 <= minrc < maxrc <= 2250\r\n");
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
masterConfig.rxConfig.calibration[i].minrc = minrc;
|
||||||
|
masterConfig.rxConfig.calibration[i].maxrc = maxrc;
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
printf("Invalid R/C channel: must be > 0 and < %u\r\n", MAX_CALIBRATED_RX_CHANNELS);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
#ifdef LED_STRIP
|
#ifdef LED_STRIP
|
||||||
static void cliLed(char *cmdline)
|
static void cliLed(char *cmdline)
|
||||||
{
|
{
|
||||||
|
@ -1467,6 +1509,10 @@ static void cliDump(char *cmdline)
|
||||||
|
|
||||||
cliAdjustmentRange("");
|
cliAdjustmentRange("");
|
||||||
|
|
||||||
|
printf("\r\n# rccal\r\n");
|
||||||
|
|
||||||
|
cliRxCalibration("");
|
||||||
|
|
||||||
cliPrint("\r\n# servo\r\n");
|
cliPrint("\r\n# servo\r\n");
|
||||||
|
|
||||||
cliServo("");
|
cliServo("");
|
||||||
|
|
|
@ -339,7 +339,20 @@ static uint16_t getRxfailValue(uint8_t channel)
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static void processRxChannels(void)
|
STATIC_UNIT_TESTED uint16_t applyRxCalibration(int sample, int minrc, int maxrc)
|
||||||
|
{
|
||||||
|
// Check special condition sample = PPM_RCVR_TIMEOUT, allow no signal value to avoid being corrupted by calibration
|
||||||
|
if (sample == 0) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
sample = scaleRange(sample, minrc, maxrc, PWM_RANGE_MIN, PWM_RANGE_MAX);
|
||||||
|
sample = MIN(MAX(PWM_PULSE_MIN, sample), PWM_PULSE_MAX);
|
||||||
|
|
||||||
|
return sample;
|
||||||
|
}
|
||||||
|
|
||||||
|
void processRxChannels(void)
|
||||||
{
|
{
|
||||||
uint8_t chan;
|
uint8_t chan;
|
||||||
|
|
||||||
|
@ -361,6 +374,11 @@ static void processRxChannels(void)
|
||||||
// sample the channel
|
// sample the channel
|
||||||
uint16_t sample = rcReadRawFunc(&rxRuntimeConfig, rawChannel);
|
uint16_t sample = rcReadRawFunc(&rxRuntimeConfig, rawChannel);
|
||||||
|
|
||||||
|
// apply the rx calibration
|
||||||
|
if (chan < MAX_CALIBRATED_RX_CHANNELS) {
|
||||||
|
sample = applyRxCalibration(sample, rxConfig->calibration[chan].minrc, rxConfig->calibration[chan].maxrc);
|
||||||
|
}
|
||||||
|
|
||||||
rxUpdateFlightChannelStatus(chan, sample);
|
rxUpdateFlightChannelStatus(chan, sample);
|
||||||
|
|
||||||
if (sample < rxConfig->rx_min_usec || sample > rxConfig->rx_max_usec || !rxSignalReceived) {
|
if (sample < rxConfig->rx_min_usec || sample > rxConfig->rx_max_usec || !rxSignalReceived) {
|
||||||
|
|
|
@ -76,6 +76,7 @@ extern const char rcChannelLetters[];
|
||||||
extern int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
extern int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
|
||||||
|
|
||||||
#define MAX_MAPPABLE_RX_INPUTS 8
|
#define MAX_MAPPABLE_RX_INPUTS 8
|
||||||
|
#define MAX_CALIBRATED_RX_CHANNELS NON_AUX_CHANNEL_COUNT
|
||||||
|
|
||||||
#define RSSI_SCALE_MIN 1
|
#define RSSI_SCALE_MIN 1
|
||||||
#define RSSI_SCALE_MAX 255
|
#define RSSI_SCALE_MAX 255
|
||||||
|
@ -91,6 +92,11 @@ typedef struct rxFailsafeChannelConfiguration_s {
|
||||||
uint8_t step;
|
uint8_t step;
|
||||||
} rxFailsafeChannelConfiguration_t;
|
} rxFailsafeChannelConfiguration_t;
|
||||||
|
|
||||||
|
typedef struct rxCalibration_s {
|
||||||
|
uint16_t minrc;
|
||||||
|
uint16_t maxrc;
|
||||||
|
} rxCalibration_t;
|
||||||
|
|
||||||
typedef struct rxConfig_s {
|
typedef struct rxConfig_s {
|
||||||
uint8_t rcmap[MAX_MAPPABLE_RX_INPUTS]; // mapping of radio channels to internal RPYTA+ order
|
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 serialrx_provider; // type of UART-based receiver (0 = spek 10, 1 = spek 11, 2 = sbus). Must be enabled by FEATURE_RX_SERIAL first.
|
||||||
|
@ -106,6 +112,7 @@ typedef struct rxConfig_s {
|
||||||
uint16_t rx_max_usec;
|
uint16_t rx_max_usec;
|
||||||
rxFailsafeChannelConfiguration_t failsafe_aux_channel_configurations[MAX_AUX_CHANNEL_COUNT];
|
rxFailsafeChannelConfiguration_t failsafe_aux_channel_configurations[MAX_AUX_CHANNEL_COUNT];
|
||||||
|
|
||||||
|
rxCalibration_t calibration[MAX_CALIBRATED_RX_CHANNELS];
|
||||||
} rxConfig_t;
|
} rxConfig_t;
|
||||||
|
|
||||||
#define REMAPPABLE_CHANNEL_COUNT (sizeof(((rxConfig_t *)0)->rcmap) / sizeof(((rxConfig_t *)0)->rcmap[0]))
|
#define REMAPPABLE_CHANNEL_COUNT (sizeof(((rxConfig_t *)0)->rcmap) / sizeof(((rxConfig_t *)0)->rcmap[0]))
|
||||||
|
|
|
@ -45,4 +45,3 @@ typedef struct
|
||||||
} TIM_TypeDef;
|
} TIM_TypeDef;
|
||||||
|
|
||||||
typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
|
typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
|
||||||
|
|
||||||
|
|
186
src/test/unit/rc_calibration_unittest.cc
Executable file
186
src/test/unit/rc_calibration_unittest.cc
Executable file
|
@ -0,0 +1,186 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
#include <limits.h>
|
||||||
|
|
||||||
|
extern "C" {
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
|
#include "io/rc_controls.h"
|
||||||
|
#include "common/maths.h"
|
||||||
|
}
|
||||||
|
|
||||||
|
#include "unittest_macros.h"
|
||||||
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
|
extern "C" {
|
||||||
|
extern uint16_t applyRxCalibration(int sample, int minrc, int maxrc);
|
||||||
|
}
|
||||||
|
|
||||||
|
TEST(RcCalibrationUnittest, TestRcCalibration)
|
||||||
|
{
|
||||||
|
// No signal, special condition
|
||||||
|
EXPECT_EQ(applyRxCalibration(0, 1000, 2000), 0);
|
||||||
|
EXPECT_EQ(applyRxCalibration(0, 1300, 1700), 0);
|
||||||
|
EXPECT_EQ(applyRxCalibration(0, 900, 2100), 0);
|
||||||
|
|
||||||
|
// Exact mapping
|
||||||
|
EXPECT_EQ(applyRxCalibration(1000, 1000, 2000), 1000);
|
||||||
|
EXPECT_EQ(applyRxCalibration(1500, 1000, 2000), 1500);
|
||||||
|
EXPECT_EQ(applyRxCalibration(2000, 1000, 2000), 2000);
|
||||||
|
EXPECT_EQ(applyRxCalibration(700, 1000, 2000), 750);
|
||||||
|
EXPECT_EQ(applyRxCalibration(2500, 1000, 2000), 2250);
|
||||||
|
|
||||||
|
// Shifted range
|
||||||
|
EXPECT_EQ(applyRxCalibration(900, 900, 1900), 1000);
|
||||||
|
EXPECT_EQ(applyRxCalibration(1400, 900, 1900), 1500);
|
||||||
|
EXPECT_EQ(applyRxCalibration(1900, 900, 1900), 2000);
|
||||||
|
EXPECT_EQ(applyRxCalibration(600, 900, 1900), 750);
|
||||||
|
EXPECT_EQ(applyRxCalibration(2500, 900, 1900), 2250);
|
||||||
|
|
||||||
|
// Narrower range than expected
|
||||||
|
EXPECT_EQ(applyRxCalibration(1300, 1300, 1700), 1000);
|
||||||
|
EXPECT_EQ(applyRxCalibration(1500, 1300, 1700), 1500);
|
||||||
|
EXPECT_EQ(applyRxCalibration(1700, 1300, 1700), 2000);
|
||||||
|
EXPECT_EQ(applyRxCalibration(700, 1300, 1700), 750);
|
||||||
|
EXPECT_EQ(applyRxCalibration(2500, 1300, 1700), 2250);
|
||||||
|
|
||||||
|
// Wider range than expected
|
||||||
|
EXPECT_EQ(applyRxCalibration(900, 900, 2100), 1000);
|
||||||
|
EXPECT_EQ(applyRxCalibration(1500, 900, 2100), 1500);
|
||||||
|
EXPECT_EQ(applyRxCalibration(2100, 900, 2100), 2000);
|
||||||
|
EXPECT_EQ(applyRxCalibration(600, 900, 2100), 750);
|
||||||
|
EXPECT_EQ(applyRxCalibration(2700, 900, 2100), 2250);
|
||||||
|
|
||||||
|
// extreme out of range
|
||||||
|
EXPECT_EQ(applyRxCalibration(1, 1000, 2000), 750);
|
||||||
|
EXPECT_EQ(applyRxCalibration(1, 1300, 1700), 750);
|
||||||
|
EXPECT_EQ(applyRxCalibration(1, 900, 2100), 750);
|
||||||
|
|
||||||
|
EXPECT_EQ(applyRxCalibration(10000, 1000, 2000), 2250);
|
||||||
|
EXPECT_EQ(applyRxCalibration(10000, 1300, 1700), 2250);
|
||||||
|
EXPECT_EQ(applyRxCalibration(10000, 900, 2100), 2250);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// stubs
|
||||||
|
extern "C" {
|
||||||
|
|
||||||
|
void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||||
|
{
|
||||||
|
UNUSED(rxRuntimeConfig);
|
||||||
|
UNUSED(callback);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool sbusInit(rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||||
|
{
|
||||||
|
UNUSED(initialRxConfig);
|
||||||
|
UNUSED(rxRuntimeConfig);
|
||||||
|
UNUSED(callback);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||||
|
{
|
||||||
|
UNUSED(rxConfig);
|
||||||
|
UNUSED(rxRuntimeConfig);
|
||||||
|
UNUSED(callback);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||||
|
{
|
||||||
|
UNUSED(rxConfig);
|
||||||
|
UNUSED(rxRuntimeConfig);
|
||||||
|
UNUSED(callback);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool sumhInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||||
|
{
|
||||||
|
UNUSED(rxConfig);
|
||||||
|
UNUSED(rxRuntimeConfig);
|
||||||
|
UNUSED(callback);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
|
||||||
|
{
|
||||||
|
UNUSED(rxConfig);
|
||||||
|
UNUSED(rxRuntimeConfig);
|
||||||
|
UNUSED(callback);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void updateActivatedModes(modeActivationCondition_t *modeActivationConditions)
|
||||||
|
{
|
||||||
|
UNUSED(modeActivationConditions);
|
||||||
|
}
|
||||||
|
|
||||||
|
void configureAdjustment(uint8_t index, uint8_t auxChannelIndex, const adjustmentConfig_t *adjustmentConfig)
|
||||||
|
{
|
||||||
|
UNUSED(index);
|
||||||
|
UNUSED(auxChannelIndex);
|
||||||
|
UNUSED(adjustmentConfig);
|
||||||
|
}
|
||||||
|
|
||||||
|
void feature(uint32_t)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
bool rxMspFrameComplete(void)
|
||||||
|
{
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void failsafeReset(void)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
bool isPPMDataBeingReceived(void)
|
||||||
|
{
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
void resetPPMDataReceivedState(void)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
void failsafeOnRxCycle(void)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
void failsafeOnValidDataReceived(void)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
void failsafeOnRxCycleStarted(void)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
void failsafeCheckPulse(uint8_t channel, uint16_t pulseDuration)
|
||||||
|
{
|
||||||
|
UNUSED(channel);
|
||||||
|
UNUSED(pulseDuration);
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue