mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-26 09:45:33 +03:00
CC3D - PPM glitch fix
This commit is contained in:
parent
46171b69a1
commit
f3374d2473
5 changed files with 33 additions and 28 deletions
|
@ -22,12 +22,14 @@ The 8 pin RC_Input connector has the following pinouts when used in RX_PPM/RX_SE
|
|||
| --- | --------- | -------------------------------- |
|
||||
| 1 | Ground | |
|
||||
| 2 | +5V | |
|
||||
| 3 | PPM Input | Enable `feature RX_PPM` |
|
||||
| 3 | Unused | |
|
||||
| 4 | SoftSerial1 TX / Sonar trigger | |
|
||||
| 5 | SoftSerial1 RX / Sonar Echo | |
|
||||
| 5 | SoftSerial1 RX / Sonar Echo / RSSI_ADC | Used either for SOFTSERIAL, SONAR or RSSI_ADC*. Only one feature can be enabled at any time. |
|
||||
| 6 | Current | Enable `feature CURRENT_METER`. Connect to the output of a current sensor, 0v-3.3v input |
|
||||
| 7 | Battery Voltage sensor | Enable `feature VBAT`. Connect to main battery using a voltage divider, 0v-3.3v input |
|
||||
| 8 | RSSI | Enable `feature RSSI_ADC`. Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input |
|
||||
| 8 | PPM Input | Enable `feature RX_PPM` |
|
||||
|
||||
*Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input.
|
||||
|
||||
The 6 pin RC_Output connector has the following pinouts when used in RX_PPM/RX_SERIAL mode
|
||||
|
||||
|
|
|
@ -886,9 +886,12 @@ void validateAndFixConfig(void)
|
|||
masterConfig.telemetryConfig.telemetry_inversion = 1;
|
||||
#endif
|
||||
|
||||
#if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1)
|
||||
if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
|
||||
#if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO)
|
||||
// shared pin
|
||||
if ((featureConfigured(FEATURE_SONAR) + featureConfigured(FEATURE_SOFTSERIAL) + featureConfigured(FEATURE_RSSI_ADC)) > 1) {
|
||||
featureClear(FEATURE_SONAR);
|
||||
featureClear(FEATURE_SOFTSERIAL);
|
||||
featureClear(FEATURE_RSSI_ADC);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -145,18 +145,17 @@ static const uint16_t airPWM[] = {
|
|||
|
||||
#ifdef CC3D
|
||||
static const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #3
|
||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4
|
||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
static const uint16_t multiPWM[] = {
|
||||
|
@ -176,7 +175,7 @@ static const uint16_t multiPWM[] = {
|
|||
};
|
||||
|
||||
static const uint16_t airPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
|
@ -187,7 +186,6 @@ static const uint16_t airPPM[] = {
|
|||
PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
|
@ -632,11 +630,6 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
#endif
|
||||
|
||||
if (type == MAP_TO_PPM_INPUT) {
|
||||
#ifdef CC3D
|
||||
if (init->useOneshot || isMotorBrushed(init->motorPwmRate)) {
|
||||
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM4);
|
||||
}
|
||||
#endif
|
||||
#ifdef SPARKY
|
||||
if (init->useOneshot || isMotorBrushed(init->motorPwmRate)) {
|
||||
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2);
|
||||
|
@ -652,6 +645,13 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
|||
channelIndex++;
|
||||
} else if (type == MAP_TO_MOTOR_OUTPUT) {
|
||||
|
||||
#ifdef CC3D
|
||||
if (init->useOneshot || isMotorBrushed(init->motorPwmRate)) {
|
||||
// Skip it if it would cause PPM capture timer to be reconfigured or manually overflowed
|
||||
if (timerHardwarePtr->tim == TIM2)
|
||||
continue;
|
||||
}
|
||||
#endif
|
||||
if (init->useOneshot) {
|
||||
|
||||
pwmOneshotMotorConfig(timerHardwarePtr, pwmIOConfiguration.motorCount);
|
||||
|
|
|
@ -68,12 +68,12 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
|
||||
#ifdef CC3D
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD}, // S1_IN - PPM
|
||||
{ TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD}, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3
|
||||
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD}, // S3_IN - SoftSerial RX
|
||||
{ TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD}, // S1_IN
|
||||
{ TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD}, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / Sonar trigger
|
||||
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD}, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC
|
||||
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD}, // S4_IN - Current
|
||||
{ TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD}, // S5_IN - Vbattery
|
||||
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD}, // S6_IN - RSSI
|
||||
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD}, // S6_IN - PPM IN
|
||||
|
||||
{ TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, GPIO_Mode_AF_PP}, // S1_OUT
|
||||
{ TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, GPIO_Mode_AF_PP}, // S2_OUT
|
||||
|
|
|
@ -103,9 +103,9 @@
|
|||
#define VBAT_ADC_GPIO_PIN GPIO_Pin_0
|
||||
#define VBAT_ADC_CHANNEL ADC_Channel_0
|
||||
|
||||
#define RSSI_ADC_GPIO GPIOA
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_1
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_1
|
||||
#define RSSI_ADC_GPIO GPIOB
|
||||
#define RSSI_ADC_GPIO_PIN GPIO_Pin_0
|
||||
#define RSSI_ADC_CHANNEL ADC_Channel_8
|
||||
|
||||
#define NAV
|
||||
//#define NAV_AUTO_MAG_DECLINATION
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue