mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 00:35:34 +03:00
Rename FEATURE_3D to FEATURE_REVERSIBLE_MOTORS
This commit is contained in:
parent
19f8a7bd56
commit
7e47809c9a
10 changed files with 18 additions and 18 deletions
|
@ -146,7 +146,7 @@ static bool commandBatchError = false;
|
||||||
static const char * const featureNames[] = {
|
static const char * const featureNames[] = {
|
||||||
"THR_VBAT_COMP", "VBAT", "TX_PROF_SEL", "BAT_PROF_AUTOSWITCH", "MOTOR_STOP",
|
"THR_VBAT_COMP", "VBAT", "TX_PROF_SEL", "BAT_PROF_AUTOSWITCH", "MOTOR_STOP",
|
||||||
"DYNAMIC_FILTERS", "SOFTSERIAL", "GPS", "RPM_FILTERS",
|
"DYNAMIC_FILTERS", "SOFTSERIAL", "GPS", "RPM_FILTERS",
|
||||||
"", "TELEMETRY", "CURRENT_METER", "3D", "",
|
"", "TELEMETRY", "CURRENT_METER", "REVERSIBLE_MOTORS", "",
|
||||||
"", "RSSI_ADC", "LED_STRIP", "DASHBOARD", "",
|
"", "RSSI_ADC", "LED_STRIP", "DASHBOARD", "",
|
||||||
"BLACKBOX", "", "TRANSPONDER", "AIRMODE",
|
"BLACKBOX", "", "TRANSPONDER", "AIRMODE",
|
||||||
"SUPEREXPO", "VTX", "", "", "PWM_SERVO_DRIVER", "PWM_OUTPUT_ENABLE",
|
"SUPEREXPO", "VTX", "", "", "PWM_SERVO_DRIVER", "PWM_OUTPUT_ENABLE",
|
||||||
|
|
|
@ -48,7 +48,7 @@ typedef enum {
|
||||||
FEATURE_UNUSED_4 = 1 << 9, // was FEATURE_SONAR
|
FEATURE_UNUSED_4 = 1 << 9, // was FEATURE_SONAR
|
||||||
FEATURE_TELEMETRY = 1 << 10,
|
FEATURE_TELEMETRY = 1 << 10,
|
||||||
FEATURE_CURRENT_METER = 1 << 11,
|
FEATURE_CURRENT_METER = 1 << 11,
|
||||||
FEATURE_3D = 1 << 12,
|
FEATURE_REVERSIBLE_MOTORS = 1 << 12,
|
||||||
FEATURE_UNUSED_5 = 1 << 13, // RX_PARALLEL_PWM
|
FEATURE_UNUSED_5 = 1 << 13, // RX_PARALLEL_PWM
|
||||||
FEATURE_UNUSED_6 = 1 << 14, // RX_MSP
|
FEATURE_UNUSED_6 = 1 << 14, // RX_MSP
|
||||||
FEATURE_RSSI_ADC = 1 << 15,
|
FEATURE_RSSI_ADC = 1 << 15,
|
||||||
|
|
|
@ -515,7 +515,7 @@ void processRx(timeUs_t currentTimeUs)
|
||||||
calculateRxChannelsAndUpdateFailsafe(currentTimeUs);
|
calculateRxChannelsAndUpdateFailsafe(currentTimeUs);
|
||||||
|
|
||||||
// in 3D mode, we need to be able to disarm by switch at any time
|
// in 3D mode, we need to be able to disarm by switch at any time
|
||||||
if (feature(FEATURE_3D)) {
|
if (feature(FEATURE_REVERSIBLE_MOTORS)) {
|
||||||
if (!IS_RC_MODE_ACTIVE(BOXARM))
|
if (!IS_RC_MODE_ACTIVE(BOXARM))
|
||||||
disarm(DISARM_SWITCH_3D);
|
disarm(DISARM_SWITCH_3D);
|
||||||
}
|
}
|
||||||
|
|
|
@ -285,7 +285,7 @@ void init(void)
|
||||||
|
|
||||||
// Some sanity checking
|
// Some sanity checking
|
||||||
if (motorConfig()->motorPwmProtocol == PWM_TYPE_BRUSHED) {
|
if (motorConfig()->motorPwmProtocol == PWM_TYPE_BRUSHED) {
|
||||||
featureClear(FEATURE_3D);
|
featureClear(FEATURE_REVERSIBLE_MOTORS);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Initialize motor and servo outpus
|
// Initialize motor and servo outpus
|
||||||
|
|
|
@ -102,9 +102,9 @@ bool areSticksDeflectedMoreThanPosHoldDeadband(void)
|
||||||
throttleStatus_e calculateThrottleStatus(void)
|
throttleStatus_e calculateThrottleStatus(void)
|
||||||
{
|
{
|
||||||
const uint16_t deadband3d_throttle = rcControlsConfig()->deadband3d_throttle;
|
const uint16_t deadband3d_throttle = rcControlsConfig()->deadband3d_throttle;
|
||||||
if (feature(FEATURE_3D) && (rxGetChannelValue(THROTTLE) > (PWM_RANGE_MIDDLE - deadband3d_throttle) && rxGetChannelValue(THROTTLE) < (PWM_RANGE_MIDDLE + deadband3d_throttle)))
|
if (feature(FEATURE_REVERSIBLE_MOTORS) && (rxGetChannelValue(THROTTLE) > (PWM_RANGE_MIDDLE - deadband3d_throttle) && rxGetChannelValue(THROTTLE) < (PWM_RANGE_MIDDLE + deadband3d_throttle)))
|
||||||
return THROTTLE_LOW;
|
return THROTTLE_LOW;
|
||||||
else if (!feature(FEATURE_3D) && (rxGetChannelValue(THROTTLE) < rxConfig()->mincheck))
|
else if (!feature(FEATURE_REVERSIBLE_MOTORS) && (rxGetChannelValue(THROTTLE) < rxConfig()->mincheck))
|
||||||
return THROTTLE_LOW;
|
return THROTTLE_LOW;
|
||||||
|
|
||||||
return THROTTLE_HIGH;
|
return THROTTLE_HIGH;
|
||||||
|
|
|
@ -287,7 +287,7 @@ void failsafeApplyControlInput(void)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case THROTTLE:
|
case THROTTLE:
|
||||||
rcCommand[idx] = feature(FEATURE_3D) ? PWM_RANGE_MIDDLE : getThrottleIdleValue();
|
rcCommand[idx] = feature(FEATURE_REVERSIBLE_MOTORS) ? PWM_RANGE_MIDDLE : getThrottleIdleValue();
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
|
@ -194,7 +194,7 @@ void applyMotorRateLimiting(const float dT)
|
||||||
{
|
{
|
||||||
static float motorPrevious[MAX_SUPPORTED_MOTORS] = { 0 };
|
static float motorPrevious[MAX_SUPPORTED_MOTORS] = { 0 };
|
||||||
|
|
||||||
if (feature(FEATURE_3D)) {
|
if (feature(FEATURE_REVERSIBLE_MOTORS)) {
|
||||||
// FIXME: Don't apply rate limiting in 3D mode
|
// FIXME: Don't apply rate limiting in 3D mode
|
||||||
for (int i = 0; i < motorCount; i++) {
|
for (int i = 0; i < motorCount; i++) {
|
||||||
motorPrevious[i] = motor[i];
|
motorPrevious[i] = motor[i];
|
||||||
|
@ -233,7 +233,7 @@ void mixerInit(void)
|
||||||
computeMotorCount();
|
computeMotorCount();
|
||||||
loadPrimaryMotorMixer();
|
loadPrimaryMotorMixer();
|
||||||
// in 3D mode, mixer gain has to be halved
|
// in 3D mode, mixer gain has to be halved
|
||||||
if (feature(FEATURE_3D)) {
|
if (feature(FEATURE_REVERSIBLE_MOTORS)) {
|
||||||
mixerScale = 0.5f;
|
mixerScale = 0.5f;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -250,7 +250,7 @@ void mixerResetDisarmedMotors(void)
|
||||||
{
|
{
|
||||||
// set disarmed motor values
|
// set disarmed motor values
|
||||||
for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||||
motor_disarmed[i] = feature(FEATURE_3D) ? flight3DConfig()->neutral3d : motorConfig()->mincommand;
|
motor_disarmed[i] = feature(FEATURE_REVERSIBLE_MOTORS) ? flight3DConfig()->neutral3d : motorConfig()->mincommand;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -263,7 +263,7 @@ void FAST_CODE NOINLINE writeMotors(void)
|
||||||
// If we use DSHOT we need to convert motorValue to DSHOT ranges
|
// If we use DSHOT we need to convert motorValue to DSHOT ranges
|
||||||
if (isMotorProtocolDigital()) {
|
if (isMotorProtocolDigital()) {
|
||||||
|
|
||||||
if (feature(FEATURE_3D)) {
|
if (feature(FEATURE_REVERSIBLE_MOTORS)) {
|
||||||
if (motor[i] >= throttleIdleValue && motor[i] <= flight3DConfig()->deadband3d_low) {
|
if (motor[i] >= throttleIdleValue && motor[i] <= flight3DConfig()->deadband3d_low) {
|
||||||
motorValue = scaleRangef(motor[i], motorConfig()->mincommand, flight3DConfig()->deadband3d_low, DSHOT_3D_DEADBAND_LOW, DSHOT_MIN_THROTTLE);
|
motorValue = scaleRangef(motor[i], motorConfig()->mincommand, flight3DConfig()->deadband3d_low, DSHOT_3D_DEADBAND_LOW, DSHOT_MIN_THROTTLE);
|
||||||
motorValue = constrain(motorValue, DSHOT_MIN_THROTTLE, DSHOT_3D_DEADBAND_LOW);
|
motorValue = constrain(motorValue, DSHOT_MIN_THROTTLE, DSHOT_3D_DEADBAND_LOW);
|
||||||
|
@ -309,7 +309,7 @@ void writeAllMotors(int16_t mc)
|
||||||
|
|
||||||
void stopMotors(void)
|
void stopMotors(void)
|
||||||
{
|
{
|
||||||
writeAllMotors(feature(FEATURE_3D) ? flight3DConfig()->neutral3d : motorConfig()->mincommand);
|
writeAllMotors(feature(FEATURE_REVERSIBLE_MOTORS) ? flight3DConfig()->neutral3d : motorConfig()->mincommand);
|
||||||
|
|
||||||
delay(50); // give the timers and ESCs a chance to react.
|
delay(50); // give the timers and ESCs a chance to react.
|
||||||
}
|
}
|
||||||
|
@ -364,7 +364,7 @@ void FAST_CODE NOINLINE mixTable(const float dT)
|
||||||
mixerThrottleCommand = constrain(globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE], throttleMin, throttleMax);
|
mixerThrottleCommand = constrain(globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE], throttleMin, throttleMax);
|
||||||
} else
|
} else
|
||||||
#endif
|
#endif
|
||||||
if (feature(FEATURE_3D)) {
|
if (feature(FEATURE_REVERSIBLE_MOTORS)) {
|
||||||
if (!ARMING_FLAG(ARMED)) throttlePrevious = PWM_RANGE_MIDDLE; // When disarmed set to mid_rc. It always results in positive direction after arming.
|
if (!ARMING_FLAG(ARMED)) throttlePrevious = PWM_RANGE_MIDDLE; // When disarmed set to mid_rc. It always results in positive direction after arming.
|
||||||
|
|
||||||
if ((rcCommand[THROTTLE] <= (PWM_RANGE_MIDDLE - rcControlsConfig()->deadband3d_throttle))) { // Out of band handling
|
if ((rcCommand[THROTTLE] <= (PWM_RANGE_MIDDLE - rcControlsConfig()->deadband3d_throttle))) { // Out of band handling
|
||||||
|
@ -424,7 +424,7 @@ void FAST_CODE NOINLINE mixTable(const float dT)
|
||||||
|
|
||||||
if (failsafeIsActive()) {
|
if (failsafeIsActive()) {
|
||||||
motor[i] = constrain(motor[i], motorConfig()->mincommand, motorConfig()->maxthrottle);
|
motor[i] = constrain(motor[i], motorConfig()->mincommand, motorConfig()->maxthrottle);
|
||||||
} else if (feature(FEATURE_3D)) {
|
} else if (feature(FEATURE_REVERSIBLE_MOTORS)) {
|
||||||
if (throttlePrevious <= (PWM_RANGE_MIDDLE - rcControlsConfig()->deadband3d_throttle)) {
|
if (throttlePrevious <= (PWM_RANGE_MIDDLE - rcControlsConfig()->deadband3d_throttle)) {
|
||||||
motor[i] = constrain(motor[i], throttleIdleValue, flight3DConfig()->deadband3d_low);
|
motor[i] = constrain(motor[i], throttleIdleValue, flight3DConfig()->deadband3d_low);
|
||||||
} else {
|
} else {
|
||||||
|
@ -437,7 +437,7 @@ void FAST_CODE NOINLINE mixTable(const float dT)
|
||||||
// Motor stop handling
|
// Motor stop handling
|
||||||
if (ARMING_FLAG(ARMED) && (getMotorStatus() != MOTOR_RUNNING)) {
|
if (ARMING_FLAG(ARMED) && (getMotorStatus() != MOTOR_RUNNING)) {
|
||||||
if (feature(FEATURE_MOTOR_STOP)) {
|
if (feature(FEATURE_MOTOR_STOP)) {
|
||||||
motor[i] = (feature(FEATURE_3D) ? PWM_RANGE_MIDDLE : motorConfig()->mincommand);
|
motor[i] = (feature(FEATURE_REVERSIBLE_MOTORS) ? PWM_RANGE_MIDDLE : motorConfig()->mincommand);
|
||||||
} else {
|
} else {
|
||||||
motor[i] = throttleIdleValue;
|
motor[i] = throttleIdleValue;
|
||||||
}
|
}
|
||||||
|
|
|
@ -247,7 +247,7 @@ void servoMixer(float dT)
|
||||||
input[INPUT_STABILIZED_YAW] = axisPID[YAW];
|
input[INPUT_STABILIZED_YAW] = axisPID[YAW];
|
||||||
|
|
||||||
// Reverse yaw servo when inverted in 3D mode only for multirotor and tricopter
|
// Reverse yaw servo when inverted in 3D mode only for multirotor and tricopter
|
||||||
if (feature(FEATURE_3D) && (rxGetChannelValue(THROTTLE) < PWM_RANGE_MIDDLE) &&
|
if (feature(FEATURE_REVERSIBLE_MOTORS) && (rxGetChannelValue(THROTTLE) < PWM_RANGE_MIDDLE) &&
|
||||||
(mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER)) {
|
(mixerConfig()->platformType == PLATFORM_MULTIROTOR || mixerConfig()->platformType == PLATFORM_TRICOPTER)) {
|
||||||
input[INPUT_STABILIZED_YAW] *= -1;
|
input[INPUT_STABILIZED_YAW] *= -1;
|
||||||
}
|
}
|
||||||
|
|
|
@ -75,7 +75,7 @@ void mspOverrideInit(void)
|
||||||
mspRcChannels[i].expiresAt = nowMs + MAX_INVALID_RX_PULSE_TIME;
|
mspRcChannels[i].expiresAt = nowMs + MAX_INVALID_RX_PULSE_TIME;
|
||||||
}
|
}
|
||||||
|
|
||||||
mspRcChannels[THROTTLE].raw = (feature(FEATURE_3D)) ? PWM_RANGE_MIDDLE : rxConfig()->rx_min_usec;
|
mspRcChannels[THROTTLE].raw = (feature(FEATURE_REVERSIBLE_MOTORS)) ? PWM_RANGE_MIDDLE : rxConfig()->rx_min_usec;
|
||||||
mspRcChannels[THROTTLE].data = mspRcChannels[THROTTLE].raw;
|
mspRcChannels[THROTTLE].data = mspRcChannels[THROTTLE].raw;
|
||||||
|
|
||||||
// Initialize ARM switch to OFF position when arming via switch is defined
|
// Initialize ARM switch to OFF position when arming via switch is defined
|
||||||
|
|
|
@ -262,7 +262,7 @@ void rxInit(void)
|
||||||
rcChannels[i].expiresAt = nowMs + MAX_INVALID_RX_PULSE_TIME;
|
rcChannels[i].expiresAt = nowMs + MAX_INVALID_RX_PULSE_TIME;
|
||||||
}
|
}
|
||||||
|
|
||||||
rcChannels[THROTTLE].raw = (feature(FEATURE_3D)) ? PWM_RANGE_MIDDLE : rxConfig()->rx_min_usec;
|
rcChannels[THROTTLE].raw = (feature(FEATURE_REVERSIBLE_MOTORS)) ? PWM_RANGE_MIDDLE : rxConfig()->rx_min_usec;
|
||||||
rcChannels[THROTTLE].data = rcChannels[THROTTLE].raw;
|
rcChannels[THROTTLE].data = rcChannels[THROTTLE].raw;
|
||||||
|
|
||||||
// Initialize ARM switch to OFF position when arming via switch is defined
|
// Initialize ARM switch to OFF position when arming via switch is defined
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue