Skip to content

Commit

Permalink
Merge branch 'rc-calibration' of
Browse files Browse the repository at this point in the history
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
  • Loading branch information
hydra committed Aug 3, 2015
2 parents 8af32e2 + 2614111 commit 27f8223
Show file tree
Hide file tree
Showing 10 changed files with 300 additions and 5 deletions.
1 change: 1 addition & 0 deletions docs/Cli.md
Original file line number Diff line number Diff line change
Expand Up @@ -92,6 +92,7 @@ Re-apply any new defaults as desired.
| `play_sound` | index, or none for next |
| `profile` | index (0 to 2) |
| `rateprofile` | index (0 to 2) |
| `rccal` | Set R/C channel calibration (stick end points) |
| `save` | save and reboot |
| `set` | name=value or blank or * for list |
| `status` | show system status |
Expand Down
35 changes: 34 additions & 1 deletion docs/Rx.md
Original file line number Diff line number Diff line change
Expand Up @@ -206,7 +206,7 @@ Use the `input_filtering_mode` CLI setting to select a mode.
| 0 | Disabled |
| 1 | Enabled |

## Receiver configuration
## Receiver configuration.

### FrSky D4R-II

Expand All @@ -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).


## 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.

2 changes: 1 addition & 1 deletion src/main/blackbox/blackbox.c
Original file line number Diff line number Diff line change
Expand Up @@ -1388,4 +1388,4 @@ void initBlackbox(void)
}
}

#endif
#endif
6 changes: 6 additions & 0 deletions src/main/config/config.c
Original file line number Diff line number Diff line change
Expand Up @@ -414,6 +414,12 @@ static void resetConf(void)
masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
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.retarded_arm = 0;
Expand Down
1 change: 0 additions & 1 deletion src/main/io/serial.c
Original file line number Diff line number Diff line change
Expand Up @@ -421,4 +421,3 @@ void evaluateOtherData(serialPort_t *serialPort, uint8_t receivedChar)
systemResetToBootloader();
}
}

46 changes: 46 additions & 0 deletions src/main/io/serial_cli.c
Original file line number Diff line number Diff line change
Expand Up @@ -117,6 +117,7 @@ static void cliSet(char *cmdline);
static void cliGet(char *cmdline);
static void cliStatus(char *cmdline);
static void cliVersion(char *cmdline);
static void cliRxCalibration(char *cmdline);

#ifdef GPS
static void cliGpsPassthrough(char *cmdline);
Expand Down Expand Up @@ -258,6 +259,7 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("rateprofile", "change rate profile",
"[<index>]", cliRateProfile),
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("serial", "configure serial ports", NULL, cliSerial),
#ifdef USE_SERVOS
Expand Down Expand Up @@ -927,6 +929,46 @@ static void cliMotorMix(char *cmdline)
#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
static void cliLed(char *cmdline)
{
Expand Down Expand Up @@ -1467,6 +1509,10 @@ static void cliDump(char *cmdline)

cliAdjustmentRange("");

printf("\r\n# rccal\r\n");

cliRxCalibration("");

cliPrint("\r\n# servo\r\n");

cliServo("");
Expand Down
20 changes: 19 additions & 1 deletion src/main/rx/rx.c
Original file line number Diff line number Diff line change
Expand Up @@ -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;

Expand All @@ -361,6 +374,11 @@ static void processRxChannels(void)
// sample the channel
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);

if (sample < rxConfig->rx_min_usec || sample > rxConfig->rx_max_usec || !rxSignalReceived) {
Expand Down
7 changes: 7 additions & 0 deletions src/main/rx/rx.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,7 @@ extern const char rcChannelLetters[];
extern int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]

#define MAX_MAPPABLE_RX_INPUTS 8
#define MAX_CALIBRATED_RX_CHANNELS NON_AUX_CHANNEL_COUNT

#define RSSI_SCALE_MIN 1
#define RSSI_SCALE_MAX 255
Expand All @@ -91,6 +92,11 @@ typedef struct rxFailsafeChannelConfiguration_s {
uint8_t step;
} rxFailsafeChannelConfiguration_t;

typedef struct rxCalibration_s {
uint16_t minrc;
uint16_t maxrc;
} rxCalibration_t;

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.
Expand All @@ -106,6 +112,7 @@ typedef struct rxConfig_s {
uint16_t rx_max_usec;
rxFailsafeChannelConfiguration_t failsafe_aux_channel_configurations[MAX_AUX_CHANNEL_COUNT];

rxCalibration_t calibration[MAX_CALIBRATED_RX_CHANNELS];
} rxConfig_t;

#define REMAPPABLE_CHANNEL_COUNT (sizeof(((rxConfig_t *)0)->rcmap) / sizeof(((rxConfig_t *)0)->rcmap[0]))
Expand Down
1 change: 0 additions & 1 deletion src/test/unit/platform.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,4 +45,3 @@ typedef struct
} TIM_TypeDef;

typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;

Loading

0 comments on commit 27f8223

Please sign in to comment.