Browse Source

RX code tidy and betaflight catchup (#605)

master
Martin Budden 8 years ago
committed by Konstantin Sharlaimov
parent
commit
46fee424be
  1. 116
      src/main/config/config.c
  2. 7
      src/main/config/config.h
  3. 2
      src/main/config/config_master.h
  4. 1
      src/main/drivers/pwm_rx.c
  5. 3
      src/main/fc/rc_controls.h
  6. 4
      src/main/rx/ibus.c
  7. 4
      src/main/rx/jetiexbus.c
  8. 2
      src/main/rx/msp.c
  9. 4
      src/main/rx/pwm.c
  10. 23
      src/main/rx/rx.c
  11. 7
      src/main/rx/rx.h
  12. 2
      src/main/rx/rx_spi.c
  13. 4
      src/main/rx/sbus.c
  14. 4
      src/main/rx/spektrum.c
  15. 4
      src/main/rx/sumd.c
  16. 8
      src/main/rx/sumh.c
  17. 4
      src/main/rx/xbus.c
  18. 2
      src/main/rx/xbus.h
  19. 6
      src/main/target/BLUEJAYF4/config.c

116
src/main/config/config.c

@ -23,6 +23,7 @@
#include "build/build_config.h"
#include "blackbox/blackbox_io.h"
#include "common/color.h"
#include "common/axis.h"
@ -33,7 +34,6 @@
#include "drivers/accgyro.h"
#include "drivers/compass.h"
#include "drivers/system.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/rx_spi.h"
@ -44,8 +44,8 @@
#include "sensors/compass.h"
#include "sensors/acceleration.h"
#include "sensors/barometer.h"
#include "sensors/boardalignment.h"
#include "sensors/battery.h"
#include "sensors/boardalignment.h"
#include "io/beeper.h"
#include "io/serial.h"
@ -59,8 +59,6 @@
#include "rx/rx.h"
#include "rx/rx_spi.h"
#include "blackbox/blackbox_io.h"
#include "telemetry/telemetry.h"
#include "flight/mixer.h"
@ -80,18 +78,13 @@
#ifndef DEFAULT_RX_FEATURE
#define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM
#endif
#ifndef RX_SPI_DEFAULT_PROTOCOL
#define RX_SPI_DEFAULT_PROTOCOL 0
#endif
#define BRUSHED_MOTORS_PWM_RATE 16000
#define BRUSHLESS_MOTORS_PWM_RATE 400
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse);
#ifndef DEFAULT_RX_FEATURE
#define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM
#endif
#ifndef RX_SPI_DEFAULT_PROTOCOL
#define RX_SPI_DEFAULT_PROTOCOL 0
#endif
master_t masterConfig; // master config struct with data independent from profiles
profile_t *currentProfile;
@ -99,6 +92,7 @@ profile_t *currentProfile;
static uint8_t currentControlRateProfileIndex = 0;
controlRateConfig_t *currentControlRateProfile;
static void resetAccelerometerTrims(flightDynamicsTrims_t * accZero, flightDynamicsTrims_t * accGain)
{
accZero->values.pitch = 0;
@ -251,7 +245,11 @@ void resetSensorAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig)
{
#ifdef BRUSHED_MOTORS
escAndServoConfig->minthrottle = 1000;
#else
escAndServoConfig->minthrottle = 1150;
#endif
escAndServoConfig->maxthrottle = 1850;
escAndServoConfig->mincommand = 1000;
escAndServoConfig->servoCenterPulse = 1500;
@ -392,8 +390,6 @@ uint16_t getCurrentMinthrottle(void)
// Default settings
static void resetConf(void)
{
int i;
// Clear all configuration
memset(&masterConfig, 0, sizeof(master_t));
setProfile(0);
@ -441,7 +437,11 @@ static void resetConf(void)
resetTelemetryConfig(&masterConfig.telemetryConfig);
#endif
#ifdef SERIALRX_PROVIDER
masterConfig.rxConfig.serialrx_provider = SERIALRX_PROVIDER;
#else
masterConfig.rxConfig.serialrx_provider = 0;
#endif
masterConfig.rxConfig.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL;
masterConfig.rxConfig.spektrum_sat_bind = 0;
masterConfig.rxConfig.midrc = 1500;
@ -450,7 +450,7 @@ static void resetConf(void)
masterConfig.rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
masterConfig.rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[i];
channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.midrc);
@ -506,7 +506,7 @@ static void resetConf(void)
resetControlRateConfig(&masterConfig.controlRateProfiles[0]);
// for (i = 0; i < CHECKBOXITEMS; i++)
// for (int i = 0; i < CHECKBOXITEMS; i++)
// cfg.activate[i] = 0;
currentProfile->mag_declination = 0;
@ -516,7 +516,11 @@ static void resetConf(void)
resetBarometerConfig(&masterConfig.barometerConfig);
// Radio
#ifdef RX_CHANNELS_TAER
parseRcChannels("TAER1234", &masterConfig.rxConfig);
#else
parseRcChannels("AETR1234", &masterConfig.rxConfig);
#endif
resetRcControlsConfig(&currentProfile->rcControlsConfig);
@ -532,7 +536,7 @@ static void resetConf(void)
#ifdef USE_SERVOS
// servos
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
currentProfile->servoConf[i].min = DEFAULT_SERVO_MIN;
currentProfile->servoConf[i].max = DEFAULT_SERVO_MAX;
currentProfile->servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
@ -551,8 +555,9 @@ static void resetConf(void)
#endif
// custom mixer. clear by defaults.
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
masterConfig.customMotorMixer[i].throttle = 0.0f;
}
#ifdef LED_STRIP
applyDefaultColors(masterConfig.colors);
@ -600,7 +605,6 @@ static void resetConf(void)
#else
masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL;
#endif
masterConfig.rxConfig.serialrx_provider = 1;
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.escAndServoConfig.minthrottle = 1000;
masterConfig.escAndServoConfig.maxthrottle = 2000;
@ -665,16 +669,16 @@ static void resetConf(void)
#endif
// copy first profile into remaining profile
for (i = 1; i < MAX_PROFILE_COUNT; i++) {
for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));
}
// copy first control rate config into remaining profile
for (i = 1; i < MAX_CONTROL_RATE_PROFILE_COUNT; i++) {
for (int i = 1; i < MAX_CONTROL_RATE_PROFILE_COUNT; i++) {
memcpy(&masterConfig.controlRateProfiles[i], currentControlRateProfile, sizeof(controlRateConfig_t));
}
for (i = 1; i < MAX_PROFILE_COUNT; i++) {
for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
masterConfig.profile[i].defaultRateProfileIndex = i % MAX_CONTROL_RATE_PROFILE_COUNT;
}
}
@ -742,45 +746,27 @@ void activateConfig(void)
void validateAndFixConfig(void)
{
if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP) || featureConfigured(FEATURE_RX_SPI))) {
featureSet(DEFAULT_RX_FEATURE);
}
if (featureConfigured(FEATURE_RX_PPM)) {
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_SPI);
}
if (featureConfigured(FEATURE_RX_MSP)) {
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_SPI);
}
featureSet(DEFAULT_RX_FEATURE);
}
if (featureConfigured(FEATURE_RX_SERIAL)) {
featureClear(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
}
if (featureConfigured(FEATURE_RX_PPM)) {
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_SPI);
}
if (featureConfigured(FEATURE_RX_SPI)) {
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_MSP);
}
if (featureConfigured(FEATURE_RX_MSP)) {
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_SPI);
}
#if defined(NAV)
// Ensure sane values of navConfig settings
validateNavConfig(&masterConfig.navConfig);
#endif
if (featureConfigured(FEATURE_RX_SERIAL)) {
featureClear(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
}
if (featureConfigured(FEATURE_SOFTSPI)) {
featureClear(FEATURE_RX_PPM | FEATURE_RX_PARALLEL_PWM | FEATURE_SOFTSERIAL | FEATURE_VBAT);
#if defined(STM32F10X)
featureClear(FEATURE_LED_STRIP);
// rssi adc needs the same ports
featureClear(FEATURE_RSSI_ADC);
// current meter needs the same ports
if (masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
featureClear(FEATURE_CURRENT_METER);
}
#endif
if (featureConfigured(FEATURE_RX_SPI)) {
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_MSP);
}
if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
featureClear(FEATURE_RX_SERIAL | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
#if defined(STM32F10X)
// rssi adc needs the same ports
featureClear(FEATURE_RSSI_ADC);
@ -788,7 +774,6 @@ void validateAndFixConfig(void)
if (masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
featureClear(FEATURE_CURRENT_METER);
}
#if defined(CC3D)
// There is a timer clash between PWM RX pins and motor output pins - this forces us to have same timer tick rate for these timers
// which is only possible when using brushless motors w/o oneshot (timer tick rate is PWM_TIMER_MHZ)
@ -812,6 +797,21 @@ void validateAndFixConfig(void)
featureClear(FEATURE_SOFTSERIAL);
}
#ifdef USE_SOFTSPI
if (featureConfigured(FEATURE_SOFTSPI)) {
featureClear(FEATURE_RX_PPM | FEATURE_RX_PARALLEL_PWM | FEATURE_SOFTSERIAL | FEATURE_VBAT);
#if defined(STM32F10X)
featureClear(FEATURE_LED_STRIP);
// rssi adc needs the same ports
featureClear(FEATURE_RSSI_ADC);
// current meter needs the same ports
if (masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
featureClear(FEATURE_CURRENT_METER);
}
#endif
}
#endif
#ifdef STM32F10X
// avoid overloading the CPU on F1 targets when using gyro sync and GPS.
if (masterConfig.gyroSync && masterConfig.gyroSyncDenominator < 2 && featureConfigured(FEATURE_GPS)) {
@ -851,7 +851,7 @@ void validateAndFixConfig(void)
}
#endif
#if defined(CC3D) && defined(DISPLAY) && defined(USE_USART3)
#if defined(CC3D) && defined(DISPLAY) && defined(USE_UART3)
if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DISPLAY)) {
featureClear(FEATURE_DISPLAY);
}
@ -904,6 +904,10 @@ void validateAndFixConfig(void)
if (!isMixerEnabled(masterConfig.mixerMode)) {
masterConfig.mixerMode = DEFAULT_MIXER;
}
#if defined(NAV)
// Ensure sane values of navConfig settings
validateNavConfig(&masterConfig.navConfig);
#endif
}
void applyAndSaveBoardAlignmentDelta(int16_t roll, int16_t pitch)

7
src/main/config/config.h

@ -17,7 +17,11 @@
#pragma once
#if FLASH_SIZE <= 128
#define MAX_PROFILE_COUNT 2
#else
#define MAX_PROFILE_COUNT 3
#endif
#define MAX_CONTROL_RATE_PROFILE_COUNT 3
#define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500
@ -93,3 +97,6 @@ bool canSoftwareSerialBeUsed(void);
void applyAndSaveBoardAlignmentDelta(int16_t roll, int16_t pitch);
uint16_t getCurrentMinthrottle(void);
struct master_s;
void targetConfiguration(struct master_s *config);

2
src/main/config/config_master.h

@ -18,7 +18,7 @@
#pragma once
// System-wide
typedef struct master_t {
typedef struct master_s {
uint8_t version;
uint16_t size;
uint8_t magic_be; // magic number, should be 0xBE

1
src/main/drivers/pwm_rx.c

@ -180,7 +180,6 @@ static void ppmOverflowCallback(timerOvrHandlerRec_t* cbRec, captureCompare_t ca
if (capture == PPM_TIMER_PERIOD - 1) {
ppmDev.overflowed = true;
}
}
static void ppmEdgeCallback(timerCCHandlerRec_t* cbRec, captureCompare_t capture)

3
src/main/fc/rc_controls.h

@ -268,3 +268,6 @@ bool isUsingNavigationModes(void);
int32_t getRcStickDeflection(int32_t axis, uint16_t midrc);
bool isModeActivationConditionPresent(modeActivationCondition_t *modeActivationConditions, boxId_e modeId);
struct escAndServoConfig_s;
struct pidProfile_s;
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, struct escAndServoConfig_s *escAndServoConfigToUse, struct pidProfile_s *pidProfileToUse);

4
src/main/rx/ibus.c

@ -49,7 +49,7 @@ static bool ibusFrameDone = false;
static uint32_t ibusChannelData[IBUS_MAX_CHANNEL];
static void ibusDataReceive(uint16_t c);
static uint16_t ibusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static uint16_t ibusReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
bool ibusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{
@ -134,7 +134,7 @@ uint8_t ibusFrameStatus(void)
return frameStatus;
}
static uint16_t ibusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t ibusReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{
UNUSED(rxRuntimeConfig);
return ibusChannelData[chan];

4
src/main/rx/jetiexbus.c

@ -208,7 +208,7 @@ static uint8_t jetiExBusRequestFrame[EXBUS_MAX_REQUEST_FRAME_SIZE];
static uint16_t jetiExBusChannelData[JETIEXBUS_CHANNEL_COUNT];
static void jetiExBusDataReceive(uint16_t c);
static uint16_t jetiExBusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static uint16_t jetiExBusReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static void jetiExBusFrameReset();
@ -416,7 +416,7 @@ uint8_t jetiExBusFrameStatus()
}
static uint16_t jetiExBusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t jetiExBusReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{
if (chan >= rxRuntimeConfig->channelCount)
return 0;

2
src/main/rx/msp.c

@ -35,7 +35,7 @@
static uint16_t mspFrame[MAX_SUPPORTED_RC_CHANNEL_COUNT];
static bool rxMspFrameDone = false;
static uint16_t rxMspReadRawRC(rxRuntimeConfig_t *rxRuntimeConfigPtr, uint8_t chan)
static uint16_t rxMspReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfigPtr, uint8_t chan)
{
UNUSED(rxRuntimeConfigPtr);
return mspFrame[chan];

4
src/main/rx/pwm.c

@ -38,13 +38,13 @@
#include "rx/rx.h"
#include "rx/pwm.h"
static uint16_t pwmReadRawRC(rxRuntimeConfig_t *rxRuntimeConfigPtr, uint8_t channel)
static uint16_t pwmReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfigPtr, uint8_t channel)
{
UNUSED(rxRuntimeConfigPtr);
return pwmRead(channel);
}
static uint16_t ppmReadRawRC(rxRuntimeConfig_t *rxRuntimeConfigPtr, uint8_t channel)
static uint16_t ppmReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfigPtr, uint8_t channel)
{
UNUSED(rxRuntimeConfigPtr);
return ppmRead(channel);

23
src/main/rx/rx.c

@ -22,12 +22,10 @@
#include <string.h>
#include "platform.h"
#include "build/build_config.h"
#include "build/build_config.h"
#include "build/debug.h"
#include "common/maths.h"
#include "config/config.h"
@ -35,19 +33,19 @@
#include "drivers/serial.h"
#include "drivers/adc.h"
#include "io/serial.h"
#include "fc/rc_controls.h"
#include "flight/failsafe.h"
#include "drivers/gpio.h"
#include "drivers/timer.h"
#include "drivers/pwm_rx.h"
#include "drivers/rx_spi.h"
#include "drivers/system.h"
#include "fc/rc_controls.h"
#include "flight/failsafe.h"
#include "io/serial.h"
#include "rx/rx.h"
#include "rx/pwm.h"
#include "rx/sbus.h"
#include "rx/spektrum.h"
@ -59,8 +57,6 @@
#include "rx/jetiexbus.h"
#include "rx/rx_spi.h"
#include "rx/rx.h"
//#define DEBUG_RX_SIGNAL_LOSS
@ -97,7 +93,7 @@ rxRuntimeConfig_t rxRuntimeConfig;
static rxConfig_t *rxConfig;
static uint8_t rcSampleIndex = 0;
static uint16_t nullReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel) {
static uint16_t nullReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel) {
UNUSED(rxRuntimeConfig);
UNUSED(channel);
@ -668,4 +664,3 @@ void updateRSSI(uint32_t currentTime)
void initRxRefreshRate(uint16_t *rxRefreshRatePtr) {
*rxRefreshRatePtr = rxRefreshRate;
}

7
src/main/rx/rx.h

@ -121,10 +121,10 @@ typedef struct rxConfig_s {
uint8_t rssi_channel;
uint8_t rssi_scale;
uint8_t rssi_ppm_invert;
uint8_t rcSmoothing; // Enable/Disable RC filtering
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 rcSmoothing; // Enable/Disable RC filtering
uint16_t rx_min_usec;
uint16_t rx_max_usec;
@ -142,12 +142,11 @@ typedef struct rxRuntimeConfig_s {
extern rxRuntimeConfig_t rxRuntimeConfig;
typedef uint16_t (*rcReadRawDataPtr)(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
struct modeActivationCondition_s;
void rxInit(rxConfig_t *rxConfig, struct modeActivationCondition_s *modeActivationConditions);
void useRxConfig(rxConfig_t *rxConfigToUse);
typedef uint16_t (*rcReadRawDataPtr)(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
void updateRx(uint32_t currentTime);
bool rxIsReceivingSignal(void);
bool rxAreFlightChannelsValid(void);

2
src/main/rx/rx_spi.c

@ -46,7 +46,7 @@ static protocolInitPtr protocolInit;
static protocolDataReceivedPtr protocolDataReceived;
static protocolSetRcDataFromPayloadPtr protocolSetRcDataFromPayload;
STATIC_UNIT_TESTED uint16_t rxSpiReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
STATIC_UNIT_TESTED uint16_t rxSpiReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
{
BUILD_BUG_ON(NRF24L01_MAX_PAYLOAD_SIZE > RX_SPI_MAX_PAYLOAD_SIZE);
if (channel >= rxRuntimeConfig->channelCount) {

4
src/main/rx/sbus.c

@ -75,7 +75,7 @@ static uint16_t sbusStateFlags = 0;
static bool sbusFrameDone = false;
static void sbusDataReceive(uint16_t c);
static uint16_t sbusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static uint16_t sbusReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static uint32_t sbusChannelData[SBUS_MAX_CHANNEL];
@ -237,7 +237,7 @@ uint8_t sbusFrameStatus(void)
return SERIAL_RX_FRAME_COMPLETE;
}
static uint16_t sbusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t sbusReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{
UNUSED(rxRuntimeConfig);
// Linear fitting values read from OpenTX-ppmus and comparing with values received by X4R

4
src/main/rx/spektrum.c

@ -61,7 +61,7 @@ static bool spekHiRes = false;
static volatile uint8_t spekFrame[SPEK_FRAME_SIZE];
static void spektrumDataReceive(uint16_t c);
static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static uint16_t spektrumReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static rxRuntimeConfig_t *rxRuntimeConfigPtr;
@ -165,7 +165,7 @@ uint8_t spektrumFrameStatus(void)
return SERIAL_RX_FRAME_COMPLETE;
}
static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t spektrumReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{
uint16_t data;

4
src/main/rx/sumd.c

@ -48,7 +48,7 @@ static uint16_t sumdChannels[SUMD_MAX_CHANNEL];
static uint16_t crc;
static void sumdDataReceive(uint16_t c);
static uint16_t sumdReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static uint16_t sumdReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
bool sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{
@ -171,7 +171,7 @@ uint8_t sumdFrameStatus(void)
return frameStatus;
}
static uint16_t sumdReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t sumdReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{
UNUSED(rxRuntimeConfig);
return sumdChannels[chan] / 8;

8
src/main/rx/sumh.c

@ -51,15 +51,11 @@ static bool sumhFrameDone = false;
static uint8_t sumhFrame[SUMH_FRAME_SIZE];
static uint32_t sumhChannels[SUMH_MAX_CHANNEL_COUNT];
static void sumhDataReceive(uint16_t c);
static uint16_t sumhReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static serialPort_t *sumhPort;
static void sumhDataReceive(uint16_t c);
static uint16_t sumhReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static uint16_t sumhReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
bool sumhInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
@ -125,7 +121,7 @@ uint8_t sumhFrameStatus(void)
return SERIAL_RX_FRAME_COMPLETE;
}
static uint16_t sumhReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t sumhReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{
UNUSED(rxRuntimeConfig);

4
src/main/rx/xbus.c

@ -82,7 +82,7 @@ static volatile uint8_t xBusFrame[XBUS_RJ01_FRAME_SIZE];
static uint16_t xBusChannelData[XBUS_RJ01_CHANNEL_COUNT];
static void xBusDataReceive(uint16_t c);
static uint16_t xBusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
static uint16_t xBusReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{
@ -303,7 +303,7 @@ uint8_t xBusFrameStatus(void)
return SERIAL_RX_FRAME_COMPLETE;
}
static uint16_t xBusReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t xBusReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
{
uint16_t data;

2
src/main/rx/xbus.h

@ -17,7 +17,5 @@
#pragma once
#include "rx/rx.h"
bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback);
uint8_t xBusFrameStatus(void);

6
src/main/target/BLUEJAYF4/config.c

@ -73,10 +73,10 @@
#include "hardware_revision.h"
// alternative defaults settings for BlueJayF4 targets
void targetConfiguration(void)
void targetConfiguration(master_t *config)
{
if (hardwareRevision == BJF4_REV1 || hardwareRevision == BJF4_REV2) {
masterConfig.sensorAlignmentConfig.gyro_align = CW180_DEG;
masterConfig.sensorAlignmentConfig.acc_align = CW180_DEG;
config->sensorAlignmentConfig.gyro_align = CW180_DEG;
config->sensorAlignmentConfig.acc_align = CW180_DEG;
}
}
Loading…
Cancel
Save