mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 00:35:39 +03:00
Initial IO remapping capability
This commit is contained in:
parent
5f47fc311b
commit
46a6e560f1
28 changed files with 506 additions and 382 deletions
127
src/main/main.c
127
src/main/main.c
|
@ -42,7 +42,6 @@
|
|||
#include "drivers/serial_uart.h"
|
||||
#include "drivers/accgyro.h"
|
||||
#include "drivers/compass.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/pwm_rx.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/adc.h"
|
||||
|
@ -247,116 +246,46 @@ void init(void)
|
|||
|
||||
mixerInit(masterConfig.mixerMode, masterConfig.customMotorMixer);
|
||||
#ifdef USE_SERVOS
|
||||
servoInit(masterConfig.customServoMixer);
|
||||
servoMixerInit(masterConfig.customServoMixer);
|
||||
#endif
|
||||
|
||||
drv_pwm_config_t pwm_params;
|
||||
memset(&pwm_params, 0, sizeof(pwm_params));
|
||||
|
||||
#ifdef SONAR
|
||||
if (feature(FEATURE_SONAR)) {
|
||||
const sonarHardware_t *sonarHardware = sonarGetHardwareConfiguration(masterConfig.batteryConfig.currentMeterType);
|
||||
if (sonarHardware) {
|
||||
pwm_params.useSonar = true;
|
||||
pwm_params.sonarIOConfig.triggerTag = sonarHardware->triggerTag;
|
||||
pwm_params.sonarIOConfig.echoTag = sonarHardware->echoTag;
|
||||
}
|
||||
uint16_t idlePulse = masterConfig.motorConfig.mincommand;
|
||||
if (feature(FEATURE_3D)) {
|
||||
idlePulse = masterConfig.flight3DConfig.neutral3d;
|
||||
}
|
||||
#endif
|
||||
|
||||
// when using airplane/wing mixer, servo/motor outputs are remapped
|
||||
if (masterConfig.mixerMode == MIXER_AIRPLANE || masterConfig.mixerMode == MIXER_FLYING_WING || masterConfig.mixerMode == MIXER_CUSTOM_AIRPLANE)
|
||||
pwm_params.airplane = true;
|
||||
else
|
||||
pwm_params.airplane = false;
|
||||
#if defined(USE_UART2) && defined(STM32F10X)
|
||||
pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
|
||||
#endif
|
||||
#ifdef STM32F303xC
|
||||
pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
|
||||
pwm_params.useUART3 = doesConfigurationUsePort(SERIAL_PORT_USART3);
|
||||
#endif
|
||||
#if defined(USE_UART2) && defined(STM32F40_41xxx)
|
||||
pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2);
|
||||
#endif
|
||||
#if defined(USE_UART6) && defined(STM32F40_41xxx)
|
||||
pwm_params.useUART6 = doesConfigurationUsePort(SERIAL_PORT_USART6);
|
||||
#endif
|
||||
pwm_params.useVbat = feature(FEATURE_VBAT);
|
||||
pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL);
|
||||
pwm_params.useParallelPWM = feature(FEATURE_RX_PARALLEL_PWM);
|
||||
pwm_params.useRSSIADC = feature(FEATURE_RSSI_ADC);
|
||||
pwm_params.useCurrentMeterADC = feature(FEATURE_CURRENT_METER)
|
||||
&& masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC;
|
||||
pwm_params.useLEDStrip = feature(FEATURE_LED_STRIP);
|
||||
pwm_params.usePPM = feature(FEATURE_RX_PPM);
|
||||
pwm_params.useSerialRx = feature(FEATURE_RX_SERIAL);
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
pwm_params.useServos = isMixerUsingServos();
|
||||
pwm_params.useChannelForwarding = feature(FEATURE_CHANNEL_FORWARDING);
|
||||
pwm_params.servoCenterPulse = masterConfig.servoConfig.servoCenterPulse;
|
||||
pwm_params.servoPwmRate = masterConfig.servoConfig.servoPwmRate;
|
||||
#endif
|
||||
|
||||
bool use_unsyncedPwm = masterConfig.motorConfig.useUnsyncedPwm || masterConfig.motorConfig.motorPwmProtocol == PWM_TYPE_CONVENTIONAL || masterConfig.motorConfig.motorPwmProtocol == PWM_TYPE_BRUSHED;
|
||||
|
||||
// Configurator feature abused for enabling Fast PWM
|
||||
pwm_params.useFastPwm = (masterConfig.motorConfig.motorPwmProtocol != PWM_TYPE_CONVENTIONAL && masterConfig.motorConfig.motorPwmProtocol != PWM_TYPE_BRUSHED);
|
||||
pwm_params.pwmProtocolType = masterConfig.motorConfig.motorPwmProtocol;
|
||||
pwm_params.motorPwmRate = use_unsyncedPwm ? masterConfig.motorConfig.motorPwmRate : 0;
|
||||
pwm_params.idlePulse = masterConfig.motorConfig.mincommand;
|
||||
if (feature(FEATURE_3D))
|
||||
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;
|
||||
|
||||
if (masterConfig.motorConfig.motorPwmProtocol == PWM_TYPE_BRUSHED) {
|
||||
featureClear(FEATURE_3D);
|
||||
pwm_params.idlePulse = 0; // brushed motors
|
||||
idlePulse = 0; // brushed motors
|
||||
}
|
||||
#ifdef CC3D
|
||||
pwm_params.useBuzzerP6 = masterConfig.use_buzzer_p6 ? true : false;
|
||||
#ifdef USE_QUAD_MIXER_ONLY
|
||||
motorInit(&masterConfig.motorConfig, idlePulse, 4);
|
||||
#else
|
||||
motorInit(&masterConfig.motorConfig, idlePulse, mixers[masterConfig.mixerMode].motorCount);
|
||||
#endif
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
if (isMixerUsingServos()) {
|
||||
//pwm_params.useChannelForwarding = feature(FEATURE_CHANNEL_FORWARDING);
|
||||
servoInit(&masterConfig.servoConfig);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifndef SKIP_RX_PWM_PPM
|
||||
pwmRxInit(masterConfig.inputFilteringMode);
|
||||
if (feature(FEATURE_RX_PPM)) {
|
||||
ppmRxInit(&masterConfig.ppmConfig, masterConfig.motorConfig.motorPwmProtocol);
|
||||
} else if (feature(FEATURE_RX_PARALLEL_PWM)) {
|
||||
pwmRxInit(&masterConfig.pwmConfig);
|
||||
}
|
||||
pwmRxSetInputFilteringMode(masterConfig.inputFilteringMode);
|
||||
#endif
|
||||
|
||||
// pwmInit() needs to be called as soon as possible for ESC compatibility reasons
|
||||
pwmOutputConfiguration_t *pwmOutputConfiguration = pwmInit(&pwm_params);
|
||||
|
||||
mixerUsePWMOutputConfiguration(pwmOutputConfiguration, use_unsyncedPwm);
|
||||
mixerUsePWMOutputConfiguration(masterConfig.motorConfig.useUnsyncedPwm);
|
||||
|
||||
systemState |= SYSTEM_STATE_MOTORS_READY;
|
||||
|
||||
#ifdef BEEPER
|
||||
beeperConfig_t beeperConfig = {
|
||||
.ioTag = IO_TAG(BEEPER),
|
||||
#ifdef BEEPER_INVERTED
|
||||
.isOD = false,
|
||||
.isInverted = true
|
||||
#else
|
||||
.isOD = true,
|
||||
.isInverted = false
|
||||
#endif
|
||||
};
|
||||
#ifdef NAZE
|
||||
if (hardwareRevision >= NAZE32_REV5) {
|
||||
// naze rev4 and below used opendrain to PNP for buzzer. Rev5 and above use PP to NPN.
|
||||
beeperConfig.isOD = false;
|
||||
beeperConfig.isInverted = true;
|
||||
}
|
||||
#endif
|
||||
/* temp until PGs are implemented. */
|
||||
#ifdef BLUEJAYF4
|
||||
if (hardwareRevision <= BJF4_REV2) {
|
||||
beeperConfig.ioTag = IO_TAG(BEEPER_OPT);
|
||||
}
|
||||
#endif
|
||||
#ifdef CC3D
|
||||
if (masterConfig.use_buzzer_p6 == 1)
|
||||
beeperConfig.ioTag = IO_TAG(BEEPER_OPT);
|
||||
#endif
|
||||
|
||||
beeperInit(&beeperConfig);
|
||||
beeperInit(&masterConfig.beeperConfig);
|
||||
#endif
|
||||
|
||||
#ifdef INVERTER
|
||||
|
@ -535,7 +464,7 @@ void init(void)
|
|||
|
||||
#ifdef SONAR
|
||||
if (feature(FEATURE_SONAR)) {
|
||||
sonarInit();
|
||||
sonarInit(&masterConfig.sonarConfig);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -569,10 +498,10 @@ void init(void)
|
|||
#ifdef USE_FLASHFS
|
||||
#ifdef NAZE
|
||||
if (hardwareRevision == NAZE32_REV5) {
|
||||
m25p16_init(IOTAG_NONE);
|
||||
m25p16_init(IO_TAG_NONE);
|
||||
}
|
||||
#elif defined(USE_FLASH_M25P16)
|
||||
m25p16_init(IOTAG_NONE);
|
||||
m25p16_init(IO_TAG_NONE);
|
||||
#endif
|
||||
|
||||
flashfsInit();
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue