Skip to content

Commit

Permalink
Refactor handling of RC input data
Browse files Browse the repository at this point in the history
- Remove globals rcData and rcRaw
- Use accesor functions to retrieve RX input data
- Refactor rx.c to use an array of structs instead of multiple arrays
- Drop the RC Preview menu from CMS. Implementing this without
globals requires significant flash and the usefulness of this menu
is questionable. If we get complains, we can add it back later.

Flash usage goes down ~250 bytes due to the removed menu. Final
binary is mostly unaffected, since LTO is able to inline the new
accessor functions in most cases.
  • Loading branch information
fiam committed Jan 19, 2019
1 parent fb0d3c4 commit 613ba2e
Show file tree
Hide file tree
Showing 18 changed files with 115 additions and 130 deletions.
2 changes: 1 addition & 1 deletion src/main/blackbox/blackbox.c
Original file line number Diff line number Diff line change
Expand Up @@ -1331,7 +1331,7 @@ static void loadMainState(timeUs_t currentTimeUs)
#endif

for (int i = 0; i < 4; i++) {
blackboxCurrent->rcData[i] = rcData[i];
blackboxCurrent->rcData[i] = rxGetChannelValue(i);
blackboxCurrent->rcCommand[i] = rcCommand[i];
}

Expand Down
6 changes: 3 additions & 3 deletions src/main/cms/cms.c
Original file line number Diff line number Diff line change
Expand Up @@ -780,9 +780,9 @@ void cmsYieldDisplay(displayPort_t *pPort, timeMs_t duration)

// Stick/key detection and key codes

#define IS_HI(X) (rcData[X] > 1750)
#define IS_LO(X) (rcData[X] < 1250)
#define IS_MID(X) (rcData[X] > 1250 && rcData[X] < 1750)
#define IS_HI(X) (rxGetChannelValue(X) > 1750)
#define IS_LO(X) (rxGetChannelValue(X) < 1250)
#define IS_MID(X) (rxGetChannelValue(X) > 1250 && rxGetChannelValue(X) < 1750)

#define KEY_NONE 0
#define KEY_UP 1
Expand Down
46 changes: 0 additions & 46 deletions src/main/cms/cms_menu_misc.c
Original file line number Diff line number Diff line change
Expand Up @@ -38,50 +38,6 @@

#include "sensors/battery.h"

//
// Misc
//

static long cmsx_menuRcConfirmBack(const OSD_Entry *self)
{
if (self && self->type == OME_Back)
return 0;
else
return -1;
}

//
// RC preview
//
static const OSD_Entry cmsx_menuRcEntries[] =
{
OSD_LABEL_ENTRY("-- RC PREV --"),

OSD_INT16_RO_ENTRY("ROLL", &rcData[ROLL]),
OSD_INT16_RO_ENTRY("PITCH", &rcData[PITCH]),
OSD_INT16_RO_ENTRY("THR", &rcData[THROTTLE]),
OSD_INT16_RO_ENTRY("YAW", &rcData[YAW]),

OSD_INT16_RO_ENTRY("AUX1", &rcData[AUX1]),
OSD_INT16_RO_ENTRY("AUX2", &rcData[AUX2]),
OSD_INT16_RO_ENTRY("AUX3", &rcData[AUX3]),
OSD_INT16_RO_ENTRY("AUX4", &rcData[AUX4]),

OSD_BACK_ENTRY,
OSD_END_ENTRY,
};

static const CMS_Menu cmsx_menuRcPreview = {
#ifdef CMS_MENU_DEBUG
.GUARD_text = "XRCPREV",
.GUARD_type = OME_MENU,
#endif
.onEnter = NULL,
.onExit = cmsx_menuRcConfirmBack,
.onGlobalExit = NULL,
.entries = cmsx_menuRcEntries
};

static const OSD_Entry menuMiscEntries[]=
{
OSD_LABEL_ENTRY("-- MISC --"),
Expand All @@ -92,8 +48,6 @@ static const OSD_Entry menuMiscEntries[]=
OSD_SETTING_ENTRY("STATS ENERGY UNIT", SETTING_OSD_STATS_ENERGY_UNIT),
#endif

OSD_SUBMENU_ENTRY("RC PREV", &cmsx_menuRcPreview),

OSD_BACK_ENTRY,
OSD_END_ENTRY,
};
Expand Down
10 changes: 5 additions & 5 deletions src/main/fc/fc_core.c
Original file line number Diff line number Diff line change
Expand Up @@ -304,9 +304,9 @@ void annexCode(void)
}
else {
// Compute ROLL PITCH and YAW command
rcCommand[ROLL] = getAxisRcCommand(rcData[ROLL], FLIGHT_MODE(MANUAL_MODE) ? currentControlRateProfile->manual.rcExpo8 : currentControlRateProfile->stabilized.rcExpo8, rcControlsConfig()->deadband);
rcCommand[PITCH] = getAxisRcCommand(rcData[PITCH], FLIGHT_MODE(MANUAL_MODE) ? currentControlRateProfile->manual.rcExpo8 : currentControlRateProfile->stabilized.rcExpo8, rcControlsConfig()->deadband);
rcCommand[YAW] = -getAxisRcCommand(rcData[YAW], FLIGHT_MODE(MANUAL_MODE) ? currentControlRateProfile->manual.rcYawExpo8 : currentControlRateProfile->stabilized.rcYawExpo8, rcControlsConfig()->yaw_deadband);
rcCommand[ROLL] = getAxisRcCommand(rxGetChannelValue(ROLL), FLIGHT_MODE(MANUAL_MODE) ? currentControlRateProfile->manual.rcExpo8 : currentControlRateProfile->stabilized.rcExpo8, rcControlsConfig()->deadband);
rcCommand[PITCH] = getAxisRcCommand(rxGetChannelValue(PITCH), FLIGHT_MODE(MANUAL_MODE) ? currentControlRateProfile->manual.rcExpo8 : currentControlRateProfile->stabilized.rcExpo8, rcControlsConfig()->deadband);
rcCommand[YAW] = -getAxisRcCommand(rxGetChannelValue(YAW), FLIGHT_MODE(MANUAL_MODE) ? currentControlRateProfile->manual.rcYawExpo8 : currentControlRateProfile->stabilized.rcYawExpo8, rcControlsConfig()->yaw_deadband);

// Apply manual control rates
if (FLIGHT_MODE(MANUAL_MODE)) {
Expand All @@ -316,7 +316,7 @@ void annexCode(void)
}

//Compute THROTTLE command
throttleValue = constrain(rcData[THROTTLE], rxConfig()->mincheck, PWM_RANGE_MAX);
throttleValue = constrain(rxGetChannelValue(THROTTLE), rxConfig()->mincheck, PWM_RANGE_MAX);
throttleValue = (uint32_t)(throttleValue - rxConfig()->mincheck) * PWM_RANGE_MIN / (PWM_RANGE_MAX - rxConfig()->mincheck); // [MINCHECK;2000] -> [0;1000]
rcCommand[THROTTLE] = rcLookupThrottle(throttleValue);

Expand Down Expand Up @@ -708,7 +708,7 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
// sticks, do not process yaw input from the rx. We do this so the
// motors do not spin up while we are trying to arm or disarm.
// Allow yaw control for tricopters if the user wants the servo to move even when unarmed.
if (isUsingSticksForArming() && rcData[THROTTLE] <= rxConfig()->mincheck
if (isUsingSticksForArming() && rxGetChannelValue(THROTTLE) <= rxConfig()->mincheck
&& !((mixerConfig()->platformType == PLATFORM_TRICOPTER) && servoConfig()->tri_unarmed_servo)
&& mixerConfig()->platformType != PLATFORM_AIRPLANE
) {
Expand Down
2 changes: 1 addition & 1 deletion src/main/fc/fc_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -478,7 +478,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF

case MSP_RC:
for (int i = 0; i < rxRuntimeConfig.channelCount; i++) {
sbufWriteU16(dst, rcRaw[i]);
sbufWriteU16(dst, rxGetRawChannelValue(i));
}
break;

Expand Down
6 changes: 3 additions & 3 deletions src/main/fc/rc_adjustments.c
Original file line number Diff line number Diff line change
Expand Up @@ -601,9 +601,9 @@ void processRcAdjustments(controlRateConfig_t *controlRateConfig, bool canUseRxD

if (adjustmentState->config->mode == ADJUSTMENT_MODE_STEP) {
int delta;
if (rcData[channelIndex] > PWM_RANGE_MIDDLE + 200) {
if (rxGetChannelValue(channelIndex) > PWM_RANGE_MIDDLE + 200) {
delta = adjustmentState->config->data.stepConfig.step;
} else if (rcData[channelIndex] < PWM_RANGE_MIDDLE - 200) {
} else if (rxGetChannelValue(channelIndex) < PWM_RANGE_MIDDLE - 200) {
delta = 0 - adjustmentState->config->data.stepConfig.step;
} else {
// returning the switch to the middle immediately resets the ready state
Expand All @@ -620,7 +620,7 @@ void processRcAdjustments(controlRateConfig_t *controlRateConfig, bool canUseRxD
#ifdef USE_INFLIGHT_PROFILE_ADJUSTMENT
} else if (adjustmentState->config->mode == ADJUSTMENT_MODE_SELECT) {
const uint16_t rangeWidth = ((2100 - 900) / adjustmentState->config->data.selectConfig.switchPositions);
const uint8_t position = (constrain(rcData[channelIndex], 900, 2100 - 1) - 900) / rangeWidth;
const uint8_t position = (constrain(rxGetChannelValue(channelIndex), 900, 2100 - 1) - 900) / rangeWidth;

applySelectAdjustment(adjustmentFunction, position);
#endif
Expand Down
26 changes: 13 additions & 13 deletions src/main/fc/rc_controls.c
Original file line number Diff line number Diff line change
Expand Up @@ -101,18 +101,18 @@ bool areSticksDeflectedMoreThanPosHoldDeadband(void)
throttleStatus_e calculateThrottleStatus(void)
{
const uint16_t deadband3d_throttle = rcControlsConfig()->deadband3d_throttle;
if (feature(FEATURE_3D) && (rcData[THROTTLE] > (PWM_RANGE_MIDDLE - deadband3d_throttle) && rcData[THROTTLE] < (PWM_RANGE_MIDDLE + deadband3d_throttle)))
if (feature(FEATURE_3D) && (rxGetChannelValue(THROTTLE) > (PWM_RANGE_MIDDLE - deadband3d_throttle) && rxGetChannelValue(THROTTLE) < (PWM_RANGE_MIDDLE + deadband3d_throttle)))
return THROTTLE_LOW;
else if (!feature(FEATURE_3D) && (rcData[THROTTLE] < rxConfig()->mincheck))
else if (!feature(FEATURE_3D) && (rxGetChannelValue(THROTTLE) < rxConfig()->mincheck))
return THROTTLE_LOW;

return THROTTLE_HIGH;
}

rollPitchStatus_e calculateRollPitchCenterStatus(void)
{
if (((rcData[PITCH] < (PWM_RANGE_MIDDLE + AIRMODE_DEADBAND)) && (rcData[PITCH] > (PWM_RANGE_MIDDLE -AIRMODE_DEADBAND)))
&& ((rcData[ROLL] < (PWM_RANGE_MIDDLE + AIRMODE_DEADBAND)) && (rcData[ROLL] > (PWM_RANGE_MIDDLE -AIRMODE_DEADBAND))))
if (((rxGetChannelValue(PITCH) < (PWM_RANGE_MIDDLE + AIRMODE_DEADBAND)) && (rxGetChannelValue(PITCH) > (PWM_RANGE_MIDDLE -AIRMODE_DEADBAND)))
&& ((rxGetChannelValue(ROLL) < (PWM_RANGE_MIDDLE + AIRMODE_DEADBAND)) && (rxGetChannelValue(ROLL) > (PWM_RANGE_MIDDLE -AIRMODE_DEADBAND))))
return CENTERED;

return NOT_CENTERED;
Expand All @@ -139,17 +139,17 @@ static void updateRcStickPositions(void)
{
stickPositions_e tmp = 0;

tmp |= ((rcData[ROLL] > rxConfig()->mincheck) ? 0x02 : 0x00) << (ROLL * 2);
tmp |= ((rcData[ROLL] < rxConfig()->maxcheck) ? 0x01 : 0x00) << (ROLL * 2);
tmp |= ((rxGetChannelValue(ROLL) > rxConfig()->mincheck) ? 0x02 : 0x00) << (ROLL * 2);
tmp |= ((rxGetChannelValue(ROLL) < rxConfig()->maxcheck) ? 0x01 : 0x00) << (ROLL * 2);

tmp |= ((rcData[PITCH] > rxConfig()->mincheck) ? 0x02 : 0x00) << (PITCH * 2);
tmp |= ((rcData[PITCH] < rxConfig()->maxcheck) ? 0x01 : 0x00) << (PITCH * 2);
tmp |= ((rxGetChannelValue(PITCH) > rxConfig()->mincheck) ? 0x02 : 0x00) << (PITCH * 2);
tmp |= ((rxGetChannelValue(PITCH) < rxConfig()->maxcheck) ? 0x01 : 0x00) << (PITCH * 2);

tmp |= ((rcData[YAW] > rxConfig()->mincheck) ? 0x02 : 0x00) << (YAW * 2);
tmp |= ((rcData[YAW] < rxConfig()->maxcheck) ? 0x01 : 0x00) << (YAW * 2);
tmp |= ((rxGetChannelValue(YAW) > rxConfig()->mincheck) ? 0x02 : 0x00) << (YAW * 2);
tmp |= ((rxGetChannelValue(YAW) < rxConfig()->maxcheck) ? 0x01 : 0x00) << (YAW * 2);

tmp |= ((rcData[THROTTLE] > rxConfig()->mincheck) ? 0x02 : 0x00) << (THROTTLE * 2);
tmp |= ((rcData[THROTTLE] < rxConfig()->maxcheck) ? 0x01 : 0x00) << (THROTTLE * 2);
tmp |= ((rxGetChannelValue(THROTTLE) > rxConfig()->mincheck) ? 0x02 : 0x00) << (THROTTLE * 2);
tmp |= ((rxGetChannelValue(THROTTLE) < rxConfig()->maxcheck) ? 0x01 : 0x00) << (THROTTLE * 2);

rcStickPositions = tmp;
}
Expand Down Expand Up @@ -350,5 +350,5 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
}

int32_t getRcStickDeflection(int32_t axis) {
return MIN(ABS(rcData[axis] - PWM_RANGE_MIDDLE), 500);
return MIN(ABS(rxGetChannelValue(axis) - PWM_RANGE_MIDDLE), 500);
}
2 changes: 1 addition & 1 deletion src/main/fc/rc_modes.c
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range)
// No need to constrain() here, since we're testing for a closed range defined
// by the channelRange_t. If channelValue has an invalid value, the test will
// be false anyway.
uint16_t channelValue = rcData[auxChannelIndex + NON_AUX_CHANNEL_COUNT];
uint16_t channelValue = rxGetChannelValue(auxChannelIndex + NON_AUX_CHANNEL_COUNT);
return (channelValue >= CHANNEL_RANGE_MIN + (range->startStep * CHANNEL_RANGE_STEP_WIDTH) &&
channelValue < CHANNEL_RANGE_MIN + (range->endStep * CHANNEL_RANGE_STEP_WIDTH));
}
Expand Down
6 changes: 3 additions & 3 deletions src/main/flight/failsafe.c
Original file line number Diff line number Diff line change
Expand Up @@ -332,9 +332,9 @@ static bool failsafeCheckStickMotion(void)
if (failsafeConfig()->failsafe_stick_motion_threshold > 0) {
uint32_t totalRcDelta = 0;

totalRcDelta += ABS(rcData[ROLL] - PWM_RANGE_MIDDLE);
totalRcDelta += ABS(rcData[PITCH] - PWM_RANGE_MIDDLE);
totalRcDelta += ABS(rcData[YAW] - PWM_RANGE_MIDDLE);
totalRcDelta += ABS(rxGetChannelValue(ROLL) - PWM_RANGE_MIDDLE);
totalRcDelta += ABS(rxGetChannelValue(PITCH) - PWM_RANGE_MIDDLE);
totalRcDelta += ABS(rxGetChannelValue(YAW) - PWM_RANGE_MIDDLE);

return totalRcDelta >= failsafeConfig()->failsafe_stick_motion_threshold;
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/flight/mixer.c
Original file line number Diff line number Diff line change
Expand Up @@ -414,7 +414,7 @@ motorStatus_e getMotorStatus(void)
return MOTOR_STOPPED_AUTO;
}

if (rcData[THROTTLE] < rxConfig()->mincheck) {
if (rxGetChannelValue(THROTTLE) < rxConfig()->mincheck) {
if ((STATE(FIXED_WING) || !isAirmodeActive()) && (!(navigationIsFlyingAutonomousMode() && navConfig()->general.flags.auto_overrides_motor_stop)) && (!failsafeIsActive())) {
return MOTOR_STOPPED_USER;
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/flight/pid.c
Original file line number Diff line number Diff line change
Expand Up @@ -361,7 +361,7 @@ void updatePIDCoefficients(void)
* Compute stick position in range of [-1.0f : 1.0f] without deadband and expo
*/
for (int axis = 0; axis < 3; axis++) {
pidState[axis].stickPosition = constrain(rcData[axis] - PWM_RANGE_MIDDLE, -500, 500) / 500.0f;
pidState[axis].stickPosition = constrain(rxGetChannelValue(axis) - PWM_RANGE_MIDDLE, -500, 500) / 500.0f;
}

// If nothing changed - don't waste time recalculating coefficients
Expand Down
36 changes: 19 additions & 17 deletions src/main/flight/servos.c
Original file line number Diff line number Diff line change
Expand Up @@ -222,7 +222,7 @@ void servoMixer(float dT)
input[INPUT_STABILIZED_YAW] = axisPID[YAW];

// Reverse yaw servo when inverted in 3D mode only for multirotor and tricopter
if (feature(FEATURE_3D) && (rcData[THROTTLE] < PWM_RANGE_MIDDLE) &&
if (feature(FEATURE_3D) && (rxGetChannelValue(THROTTLE) < PWM_RANGE_MIDDLE) &&
(mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER)) {
input[INPUT_STABILIZED_YAW] *= -1;
}
Expand All @@ -246,22 +246,24 @@ void servoMixer(float dT)
// 2000 - 1500 = +500
// 1500 - 1500 = 0
// 1000 - 1500 = -500
input[INPUT_RC_ROLL] = rcData[ROLL] - PWM_RANGE_MIDDLE;
input[INPUT_RC_PITCH] = rcData[PITCH] - PWM_RANGE_MIDDLE;
input[INPUT_RC_YAW] = rcData[YAW] - PWM_RANGE_MIDDLE;
input[INPUT_RC_THROTTLE] = rcData[THROTTLE] - PWM_RANGE_MIDDLE;
input[INPUT_RC_CH5] = rcData[AUX1] - PWM_RANGE_MIDDLE;
input[INPUT_RC_CH6] = rcData[AUX2] - PWM_RANGE_MIDDLE;
input[INPUT_RC_CH7] = rcData[AUX3] - PWM_RANGE_MIDDLE;
input[INPUT_RC_CH8] = rcData[AUX4] - PWM_RANGE_MIDDLE;
input[INPUT_RC_CH9] = rcData[AUX5] - PWM_RANGE_MIDDLE;
input[INPUT_RC_CH10] = rcData[AUX6] - PWM_RANGE_MIDDLE;
input[INPUT_RC_CH11] = rcData[AUX7] - PWM_RANGE_MIDDLE;
input[INPUT_RC_CH12] = rcData[AUX8] - PWM_RANGE_MIDDLE;
input[INPUT_RC_CH13] = rcData[AUX9] - PWM_RANGE_MIDDLE;
input[INPUT_RC_CH14] = rcData[AUX10] - PWM_RANGE_MIDDLE;
input[INPUT_RC_CH15] = rcData[AUX11] - PWM_RANGE_MIDDLE;
input[INPUT_RC_CH16] = rcData[AUX12] - PWM_RANGE_MIDDLE;
#define GET_RX_CHANNEL_INPUT(x) (rxGetChannelValue(x) - PWM_RANGE_MIDDLE)
input[INPUT_RC_ROLL] = GET_RX_CHANNEL_INPUT(ROLL);
input[INPUT_RC_PITCH] = GET_RX_CHANNEL_INPUT(PITCH);
input[INPUT_RC_YAW] = GET_RX_CHANNEL_INPUT(YAW);
input[INPUT_RC_THROTTLE] = GET_RX_CHANNEL_INPUT(THROTTLE);
input[INPUT_RC_CH5] = GET_RX_CHANNEL_INPUT(AUX1);
input[INPUT_RC_CH6] = GET_RX_CHANNEL_INPUT(AUX2);
input[INPUT_RC_CH7] = GET_RX_CHANNEL_INPUT(AUX3);
input[INPUT_RC_CH8] = GET_RX_CHANNEL_INPUT(AUX4);
input[INPUT_RC_CH9] = GET_RX_CHANNEL_INPUT(AUX5);
input[INPUT_RC_CH10] = GET_RX_CHANNEL_INPUT(AUX6);
input[INPUT_RC_CH11] = GET_RX_CHANNEL_INPUT(AUX7);
input[INPUT_RC_CH12] = GET_RX_CHANNEL_INPUT(AUX8);
input[INPUT_RC_CH13] = GET_RX_CHANNEL_INPUT(AUX9);
input[INPUT_RC_CH14] = GET_RX_CHANNEL_INPUT(AUX10);
input[INPUT_RC_CH15] = GET_RX_CHANNEL_INPUT(AUX11);
input[INPUT_RC_CH16] = GET_RX_CHANNEL_INPUT(AUX12);
#undef GET_RX_CHANNEL_INPUT

for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
servo[i] = 0;
Expand Down
4 changes: 2 additions & 2 deletions src/main/io/ledstrip.c
Original file line number Diff line number Diff line change
Expand Up @@ -727,7 +727,7 @@ static void applyLedThrustRingLayer(bool updateNow, timeUs_t *timer)
if (updateNow) {
rotationPhase = rotationPhase > 0 ? rotationPhase - 1 : ledCounts.ringSeqLen - 1;

int scale = scaledThrottle; // ARMING_FLAG(ARMED) ? scaleRange(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX, 10, 100) : 10;
int scale = scaledThrottle; // ARMING_FLAG(ARMED) ? scaleRange(rxGetChannelValue(THROTTLE), PWM_RANGE_MIN, PWM_RANGE_MAX, 10, 100) : 10;
*timer += LED_STRIP_HZ(5) * 10 / scale; // 5 - 50Hz update rate
}

Expand Down Expand Up @@ -949,7 +949,7 @@ void ledStripUpdate(timeUs_t currentTimeUs)

// apply all layers; triggered timed functions has to update timers

scaledThrottle = ARMING_FLAG(ARMED) ? scaleRange(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX, 10, 100) : 10;
scaledThrottle = ARMING_FLAG(ARMED) ? scaleRange(rxGetChannelValue(THROTTLE), PWM_RANGE_MIN, PWM_RANGE_MAX, 10, 100) : 10;

applyLedFixedLayers();

Expand Down
2 changes: 1 addition & 1 deletion src/main/io/osd.c
Original file line number Diff line number Diff line change
Expand Up @@ -801,7 +801,7 @@ static void osdFormatThrottlePosition(char *buff, bool autoThr, textAttributes_t
{
buff[0] = SYM_BLANK;
buff[1] = SYM_THR;
int16_t thr = rcData[THROTTLE];
int16_t thr = rxGetChannelValue(THROTTLE);
if (autoThr && navigationIsControllingThrottle()) {
buff[0] = SYM_AUTO_THR0;
buff[1] = SYM_AUTO_THR1;
Expand Down
6 changes: 3 additions & 3 deletions src/main/io/rcdevice_cam.c
Original file line number Diff line number Diff line change
Expand Up @@ -34,9 +34,9 @@

#ifdef USE_RCDEVICE

#define IS_HI(X) (rcData[X] > 1750)
#define IS_LO(X) (rcData[X] < 1250)
#define IS_MID(X) (rcData[X] > 1250 && rcData[X] < 1750)
#define IS_HI(X) (rxGetChannelValue(X) > 1750)
#define IS_LO(X) (rxGetChannelValue(X) < 1250)
#define IS_MID(X) (rxGetChannelValue(X) > 1250 && rxGetChannelValue(X) < 1750)
static runcamDevice_t runcamDevice;
runcamDevice_t *camDevice = &runcamDevice;
rcdeviceSwitchState_t switchStates[BOXCAMERA3 - BOXCAMERA1 + 1];
Expand Down
Loading

0 comments on commit 613ba2e

Please sign in to comment.