mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 23:05:19 +03:00
Small PPM fixes and updates to REVO
This commit is contained in:
parent
f21037ad37
commit
f823a81540
2 changed files with 17 additions and 14 deletions
|
@ -109,7 +109,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||||
#else
|
#else
|
||||||
setup = hardwareMaps[i];
|
setup = hardwareMaps[i];
|
||||||
#endif
|
#endif
|
||||||
|
TIM_TypeDef* ppmTimer = NULL;
|
||||||
for (i = 0; i < USABLE_TIMER_CHANNEL_COUNT && setup[i] != 0xFFFF; i++) {
|
for (i = 0; i < USABLE_TIMER_CHANNEL_COUNT && setup[i] != 0xFFFF; i++) {
|
||||||
uint8_t timerIndex = setup[i] & 0x00FF;
|
uint8_t timerIndex = setup[i] & 0x00FF;
|
||||||
uint8_t type = (setup[i] & 0xFF00) >> 8;
|
uint8_t type = (setup[i] & 0xFF00) >> 8;
|
||||||
|
@ -162,13 +162,13 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef RSSI_ADC_GPIO
|
#ifdef RSSI_ADC_PIN
|
||||||
if (init->useRSSIADC && timerHardwarePtr->tag == IO_TAG(RSSI_ADC_PIN)) {
|
if (init->useRSSIADC && timerHardwarePtr->tag == IO_TAG(RSSI_ADC_PIN)) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef CURRENT_METER_ADC_GPIO
|
#ifdef CURRENT_METER_ADC_PIN
|
||||||
if (init->useCurrentMeterADC && timerHardwarePtr->tag == IO_TAG(CURRENT_METER_ADC_PIN)) {
|
if (init->useCurrentMeterADC && timerHardwarePtr->tag == IO_TAG(CURRENT_METER_ADC_PIN)) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
@ -292,11 +292,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||||
|
|
||||||
if (type == MAP_TO_PPM_INPUT) {
|
if (type == MAP_TO_PPM_INPUT) {
|
||||||
#ifndef SKIP_RX_PWM_PPM
|
#ifndef SKIP_RX_PWM_PPM
|
||||||
#if defined(SPARKY) || defined(ALIENFLIGHTF3)
|
ppmTimer = timerHardwarePtr->tim;
|
||||||
if (!(init->pwmProtocolType == PWM_TYPE_CONVENTIONAL)) {
|
|
||||||
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2, init->pwmProtocolType);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
ppmInConfig(timerHardwarePtr);
|
ppmInConfig(timerHardwarePtr);
|
||||||
#endif
|
#endif
|
||||||
} else if (type == MAP_TO_PWM_INPUT) {
|
} else if (type == MAP_TO_PWM_INPUT) {
|
||||||
|
@ -313,6 +309,12 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
if (init->usePPM) {
|
||||||
|
if (init->pwmProtocolType != PWM_TYPE_CONVENTIONAL && timerHardwarePtr->tim == ppmTimer) {
|
||||||
|
ppmAvoidPWMTimerClash(timerHardwarePtr, ppmTimer, init->pwmProtocolType);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
if (init->useFastPwm) {
|
if (init->useFastPwm) {
|
||||||
pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse, init->pwmProtocolType);
|
pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse, init->pwmProtocolType);
|
||||||
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM | PWM_PF_OUTPUT_PROTOCOL_ONESHOT;
|
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM | PWM_PF_OUTPUT_PROTOCOL_ONESHOT;
|
||||||
|
|
|
@ -20,6 +20,7 @@
|
||||||
#include <platform.h>
|
#include <platform.h>
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/pwm_mapping.h"
|
#include "drivers/pwm_mapping.h"
|
||||||
|
#include "drivers/timer.h"
|
||||||
|
|
||||||
const uint16_t multiPPM[] = {
|
const uint16_t multiPPM[] = {
|
||||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||||
|
@ -29,11 +30,11 @@ const uint16_t multiPPM[] = {
|
||||||
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||||
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
PWM2 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
|
||||||
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
PWM3 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
|
||||||
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
|
||||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
|
||||||
PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
PWM6 | (MAP_TO_SERVO_OUTPUT << 8), // Swap to servo if needed
|
||||||
0xFFFF
|
0xFFFF
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue