mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 00:35:39 +03:00
Merge branch 'master' into bfdev-configurable-baro
This commit is contained in:
commit
a6e3ca2345
9 changed files with 115 additions and 90 deletions
|
@ -52,29 +52,6 @@
|
|||
#include "io/flashfs.h"
|
||||
#include "io/beeper.h"
|
||||
|
||||
|
||||
#ifdef USE_FLASHFS
|
||||
static long cmsx_EraseFlash(displayPort_t *pDisplay, const void *ptr)
|
||||
{
|
||||
UNUSED(ptr);
|
||||
|
||||
displayClearScreen(pDisplay);
|
||||
displayWrite(pDisplay, 5, 3, "ERASING FLASH...");
|
||||
displayResync(pDisplay); // Was max7456RefreshAll(); Why at this timing?
|
||||
|
||||
flashfsEraseCompletely();
|
||||
while (!flashfsIsReady()) {
|
||||
delay(100);
|
||||
}
|
||||
|
||||
beeper(BEEPER_BLACKBOX_ERASE);
|
||||
displayClearScreen(pDisplay);
|
||||
displayResync(pDisplay); // Was max7456RefreshAll(); wedges during heavy SPI?
|
||||
|
||||
return 0;
|
||||
}
|
||||
#endif // USE_FLASHFS
|
||||
|
||||
static const char * const cmsx_BlackboxDeviceNames[] = {
|
||||
"NONE",
|
||||
"FLASH ",
|
||||
|
@ -163,6 +140,31 @@ static void cmsx_Blackbox_GetDeviceStatus()
|
|||
tfp_sprintf(cmsx_BlackboxDeviceStorageFree, "%ld%s", storageFree, unit);
|
||||
}
|
||||
|
||||
#ifdef USE_FLASHFS
|
||||
static long cmsx_EraseFlash(displayPort_t *pDisplay, const void *ptr)
|
||||
{
|
||||
UNUSED(ptr);
|
||||
|
||||
displayClearScreen(pDisplay);
|
||||
displayWrite(pDisplay, 5, 3, "ERASING FLASH...");
|
||||
displayResync(pDisplay); // Was max7456RefreshAll(); Why at this timing?
|
||||
|
||||
flashfsEraseCompletely();
|
||||
while (!flashfsIsReady()) {
|
||||
delay(100);
|
||||
}
|
||||
|
||||
beeper(BEEPER_BLACKBOX_ERASE);
|
||||
displayClearScreen(pDisplay);
|
||||
displayResync(pDisplay); // Was max7456RefreshAll(); wedges during heavy SPI?
|
||||
|
||||
// Update storage device status to show new used space amount
|
||||
cmsx_Blackbox_GetDeviceStatus();
|
||||
|
||||
return 0;
|
||||
}
|
||||
#endif // USE_FLASHFS
|
||||
|
||||
static long cmsx_Blackbox_onEnter(void)
|
||||
{
|
||||
cmsx_Blackbox_GetDeviceStatus();
|
||||
|
|
|
@ -88,6 +88,7 @@ static long cmsx_profileIndexOnChange(displayPort_t *displayPort, const void *pt
|
|||
UNUSED(ptr);
|
||||
|
||||
pidProfileIndex = tmpPidProfileIndex - 1;
|
||||
changePidProfile(pidProfileIndex);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
@ -98,6 +99,7 @@ static long cmsx_rateProfileIndexOnChange(displayPort_t *displayPort, const void
|
|||
UNUSED(ptr);
|
||||
|
||||
rateProfileIndex = tmpRateProfileIndex - 1;
|
||||
changeControlRateProfile(rateProfileIndex);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
|
|
@ -66,8 +66,8 @@ OSD_Entry menuOsdActiveElemsEntries[] =
|
|||
{"CROSSHAIRS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_CROSSHAIRS], 0},
|
||||
{"HORIZON", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ARTIFICIAL_HORIZON], 0},
|
||||
{"HORIZON SIDEBARS", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_HORIZON_SIDEBARS], 0},
|
||||
{"TIMER 1", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_TIMER_1], 0},
|
||||
{"TIMER 2", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_TIMER_2], 0},
|
||||
{"TIMER 1", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ITEM_TIMER_1], 0},
|
||||
{"TIMER 2", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ITEM_TIMER_2], 0},
|
||||
{"FLY MODE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_FLYMODE], 0},
|
||||
{"NAME", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_CRAFT_NAME], 0},
|
||||
{"THROTTLE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_THROTTLE_POS], 0},
|
||||
|
|
|
@ -311,13 +311,14 @@ void motorDevInit(const motorDevConfig_t *motorConfig, uint16_t idlePulse, uint8
|
|||
#endif
|
||||
|
||||
/* standard PWM outputs */
|
||||
const unsigned pwmRateHz = useUnsyncedPwm ? motorConfig->motorPwmRate : ceilf(1 / (sMin + sLen * 2));
|
||||
// margin of safety is 4 periods when unsynced
|
||||
const unsigned pwmRateHz = useUnsyncedPwm ? motorConfig->motorPwmRate : ceilf(1 / ((sMin + sLen) * 4));
|
||||
|
||||
const uint32_t clock = timerClock(timerHardware->tim);
|
||||
/* used to find the desired timer frequency for max resolution */
|
||||
const unsigned prescaler = ((clock / pwmRateHz) + 0xffff) / 0x10000; /* rounding up */
|
||||
const uint32_t hz = clock / prescaler;
|
||||
const unsigned period = hz / pwmRateHz;
|
||||
const unsigned period = useUnsyncedPwm ? hz / pwmRateHz : 0xffff;
|
||||
|
||||
/*
|
||||
if brushed then it is the entire length of the period.
|
||||
|
|
|
@ -147,6 +147,7 @@ static uint32_t bufferIndex = 0;
|
|||
static bool configIsInCopy = false;
|
||||
|
||||
static const char* const emptyName = "-";
|
||||
static const char* const emptryString = "";
|
||||
|
||||
#ifndef USE_QUAD_MIXER_ONLY
|
||||
// sync this with mixerMode_e
|
||||
|
@ -883,7 +884,7 @@ static void cliSerialPassthrough(char *cmdline)
|
|||
serialPortUsage_t *passThroughPortUsage = findSerialPortUsageByIdentifier(id);
|
||||
if (!passThroughPortUsage || passThroughPortUsage->serialPort == NULL) {
|
||||
if (!baud) {
|
||||
cliPrint("closed, specify baud.\r\n");
|
||||
cliPrintLine("closed, specify baud.");
|
||||
return;
|
||||
}
|
||||
if (!mode)
|
||||
|
@ -893,7 +894,7 @@ static void cliSerialPassthrough(char *cmdline)
|
|||
baud, mode,
|
||||
SERIAL_NOT_INVERTED);
|
||||
if (!passThroughPort) {
|
||||
cliPrint("could not be opened.\r\n");
|
||||
cliPrintLine("could not be opened.");
|
||||
return;
|
||||
}
|
||||
cliPrintf("opened, baud = %d.\r\n", baud);
|
||||
|
@ -901,7 +902,7 @@ static void cliSerialPassthrough(char *cmdline)
|
|||
passThroughPort = passThroughPortUsage->serialPort;
|
||||
// If the user supplied a mode, override the port's mode, otherwise
|
||||
// leave the mode unchanged. serialPassthrough() handles one-way ports.
|
||||
cliPrint("already open.\r\n");
|
||||
cliPrintLine("already open.");
|
||||
if (mode && passThroughPort->mode != mode) {
|
||||
cliPrintf("mode changed from %d to %d.\r\n",
|
||||
passThroughPort->mode, mode);
|
||||
|
@ -914,7 +915,7 @@ static void cliSerialPassthrough(char *cmdline)
|
|||
}
|
||||
}
|
||||
|
||||
cliPrint("Forwarding, power cycle to exit.\r\n");
|
||||
cliPrintLine("Forwarding, power cycle to exit.");
|
||||
|
||||
serialPassthrough(cliPort, passThroughPort, NULL, NULL);
|
||||
}
|
||||
|
@ -1911,12 +1912,15 @@ static void printFeature(uint8_t dumpMask, const featureConfig_t *featureConfig,
|
|||
{
|
||||
const uint32_t mask = featureConfig->enabledFeatures;
|
||||
const uint32_t defaultMask = featureConfigDefault->enabledFeatures;
|
||||
for (uint32_t i = 0; featureNames[i]; i++) { // disable all feature first
|
||||
for (uint32_t i = 0; featureNames[i]; i++) { // disabled features first
|
||||
if (strcmp(featureNames[i], emptryString) != 0) { //Skip unused
|
||||
const char *format = "feature -%s";
|
||||
cliDefaultPrintLinef(dumpMask, (defaultMask | ~mask) & (1 << i), format, featureNames[i]);
|
||||
cliDumpPrintLinef(dumpMask, (~defaultMask | mask) & (1 << i), format, featureNames[i]);
|
||||
}
|
||||
for (uint32_t i = 0; featureNames[i]; i++) { // reenable what we want.
|
||||
}
|
||||
for (uint32_t i = 0; featureNames[i]; i++) { // enabled features
|
||||
if (strcmp(featureNames[i], emptryString) != 0) { //Skip unused
|
||||
const char *format = "feature %s";
|
||||
if (defaultMask & (1 << i)) {
|
||||
cliDefaultPrintLinef(dumpMask, (~defaultMask | mask) & (1 << i), format, featureNames[i]);
|
||||
|
@ -1926,6 +1930,7 @@ static void printFeature(uint8_t dumpMask, const featureConfig_t *featureConfig,
|
|||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void cliFeature(char *cmdline)
|
||||
{
|
||||
|
@ -1946,7 +1951,7 @@ static void cliFeature(char *cmdline)
|
|||
for (uint32_t i = 0; ; i++) {
|
||||
if (featureNames[i] == NULL)
|
||||
break;
|
||||
if (strcmp(featureNames[i], "") != 0) //Skip unused
|
||||
if (strcmp(featureNames[i], emptryString) != 0) //Skip unused
|
||||
cliPrintf(" %s", featureNames[i]);
|
||||
}
|
||||
cliPrintLinefeed();
|
||||
|
@ -2296,13 +2301,33 @@ void printEscInfo(const uint8_t *escInfoBytes, uint8_t bytesRead)
|
|||
cliPrintLinef("3D: %s", escInfoBytes[17] ? "on" : "off");
|
||||
}
|
||||
} else {
|
||||
cliPrint("Checksum error.");
|
||||
cliPrintLine("Checksum error.");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (!escInfoReceived) {
|
||||
cliPrint("No info.");
|
||||
cliPrintLine("No info.");
|
||||
}
|
||||
}
|
||||
|
||||
static void writeDshotCommand(uint8_t escIndex, uint8_t command)
|
||||
{
|
||||
uint8_t escInfoBuffer[ESC_INFO_V2_EXPECTED_FRAME_SIZE];
|
||||
if (command == DSHOT_CMD_ESC_INFO) {
|
||||
cliPrintLinef("Info for ESC %d:", escIndex);
|
||||
|
||||
delay(10); // Wait for potential ESC telemetry transmission to finish
|
||||
|
||||
startEscDataRead(escInfoBuffer, ESC_INFO_V2_EXPECTED_FRAME_SIZE);
|
||||
}
|
||||
|
||||
pwmWriteDshotCommand(escIndex, command);
|
||||
|
||||
if (command == DSHOT_CMD_ESC_INFO) {
|
||||
delay(10);
|
||||
|
||||
printEscInfo(escInfoBuffer, getNumberEscBytesRead());
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -2334,34 +2359,19 @@ static void cliDshotProg(char *cmdline)
|
|||
if (command >= 0 && command < DSHOT_MIN_THROTTLE) {
|
||||
if (escIndex == ALL_MOTORS) {
|
||||
for (unsigned i = 0; i < getMotorCount(); i++) {
|
||||
pwmWriteDshotCommand(i, command);
|
||||
writeDshotCommand(i, command);
|
||||
}
|
||||
|
||||
cliPrintf("Command %d written.\r\n", command);
|
||||
} else {
|
||||
uint8_t escInfoBuffer[ESC_INFO_V2_EXPECTED_FRAME_SIZE];
|
||||
if (command == DSHOT_CMD_ESC_INFO) {
|
||||
delay(10); // Wait for potential ESC telemetry transmission to finish
|
||||
|
||||
startEscDataRead(escInfoBuffer, ESC_INFO_V2_EXPECTED_FRAME_SIZE);
|
||||
writeDshotCommand(escIndex, command);
|
||||
}
|
||||
|
||||
pwmWriteDshotCommand(escIndex, command);
|
||||
|
||||
if (command == DSHOT_CMD_ESC_INFO) {
|
||||
delay(10);
|
||||
|
||||
printEscInfo(escInfoBuffer, getNumberEscBytesRead());
|
||||
} else {
|
||||
cliPrintf("Command %d written.\r\n", command);
|
||||
}
|
||||
}
|
||||
cliPrintLinef("Command %d written.", command);
|
||||
|
||||
if (command <= 5) {
|
||||
delay(10); // wait for sound output to finish
|
||||
}
|
||||
} else {
|
||||
cliPrintf("Invalid command, range 1 to %d.\r\n", DSHOT_MIN_THROTTLE - 1);
|
||||
cliPrintLinef("Invalid command, range 1 to %d.", DSHOT_MIN_THROTTLE - 1);
|
||||
}
|
||||
|
||||
break;
|
||||
|
|
|
@ -1597,7 +1597,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
break;
|
||||
|
||||
case MSP_SET_RC_TUNING:
|
||||
if (dataSize >= 10) {
|
||||
if (sbufBytesRemaining(src) >= 10) {
|
||||
currentControlRateProfile->rcRate8 = sbufReadU8(src);
|
||||
currentControlRateProfile->rcExpo8 = sbufReadU8(src);
|
||||
for (int i = 0; i < 3; i++) {
|
||||
|
@ -1609,10 +1609,10 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
currentControlRateProfile->thrMid8 = sbufReadU8(src);
|
||||
currentControlRateProfile->thrExpo8 = sbufReadU8(src);
|
||||
currentControlRateProfile->tpa_breakpoint = sbufReadU16(src);
|
||||
if (dataSize >= 11) {
|
||||
if (sbufBytesRemaining(src) >= 1) {
|
||||
currentControlRateProfile->rcYawExpo8 = sbufReadU8(src);
|
||||
}
|
||||
if (dataSize >= 12) {
|
||||
if (sbufBytesRemaining(src) >= 1) {
|
||||
currentControlRateProfile->rcYawRate8 = sbufReadU8(src);
|
||||
}
|
||||
generateThrottleCurve();
|
||||
|
@ -1738,17 +1738,17 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
gyroConfigMutable()->gyro_soft_lpf_hz = sbufReadU8(src);
|
||||
currentPidProfile->dterm_lpf_hz = sbufReadU16(src);
|
||||
currentPidProfile->yaw_lpf_hz = sbufReadU16(src);
|
||||
if (dataSize > 5) {
|
||||
if (sbufBytesRemaining(src) >= 8) {
|
||||
gyroConfigMutable()->gyro_soft_notch_hz_1 = sbufReadU16(src);
|
||||
gyroConfigMutable()->gyro_soft_notch_cutoff_1 = sbufReadU16(src);
|
||||
currentPidProfile->dterm_notch_hz = sbufReadU16(src);
|
||||
currentPidProfile->dterm_notch_cutoff = sbufReadU16(src);
|
||||
}
|
||||
if (dataSize > 13) {
|
||||
if (sbufBytesRemaining(src) >= 4) {
|
||||
gyroConfigMutable()->gyro_soft_notch_hz_2 = sbufReadU16(src);
|
||||
gyroConfigMutable()->gyro_soft_notch_cutoff_2 = sbufReadU16(src);
|
||||
}
|
||||
if (dataSize > 17) {
|
||||
if (sbufBytesRemaining(src) >= 1) {
|
||||
currentPidProfile->dterm_filter_type = sbufReadU8(src);
|
||||
}
|
||||
// reinitialize the gyro filters with the new values
|
||||
|
@ -1771,11 +1771,11 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
sbufReadU8(src); // reserved
|
||||
currentPidProfile->rateAccelLimit = sbufReadU16(src);
|
||||
currentPidProfile->yawRateAccelLimit = sbufReadU16(src);
|
||||
if (dataSize > 17) {
|
||||
if (sbufBytesRemaining(src) >= 2) {
|
||||
currentPidProfile->levelAngleLimit = sbufReadU8(src);
|
||||
currentPidProfile->levelSensitivity = sbufReadU8(src);
|
||||
}
|
||||
if (dataSize > 19) {
|
||||
if (sbufBytesRemaining(src) >= 4) {
|
||||
currentPidProfile->itermThrottleThreshold = sbufReadU16(src);
|
||||
currentPidProfile->itermAcceleratorGain = sbufReadU16(src);
|
||||
}
|
||||
|
@ -1928,21 +1928,21 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
rxConfigMutable()->midrc = sbufReadU16(src);
|
||||
rxConfigMutable()->mincheck = sbufReadU16(src);
|
||||
rxConfigMutable()->spektrum_sat_bind = sbufReadU8(src);
|
||||
if (dataSize > 8) {
|
||||
if (sbufBytesRemaining(src) >= 4) {
|
||||
rxConfigMutable()->rx_min_usec = sbufReadU16(src);
|
||||
rxConfigMutable()->rx_max_usec = sbufReadU16(src);
|
||||
}
|
||||
if (dataSize > 12) {
|
||||
if (sbufBytesRemaining(src) >= 4) {
|
||||
rxConfigMutable()->rcInterpolation = sbufReadU8(src);
|
||||
rxConfigMutable()->rcInterpolationInterval = sbufReadU8(src);
|
||||
rxConfigMutable()->airModeActivateThreshold = sbufReadU16(src);
|
||||
}
|
||||
if (dataSize > 16) {
|
||||
if (sbufBytesRemaining(src) >= 6) {
|
||||
rxConfigMutable()->rx_spi_protocol = sbufReadU8(src);
|
||||
rxConfigMutable()->rx_spi_id = sbufReadU32(src);
|
||||
rxConfigMutable()->rx_spi_rf_channel_count = sbufReadU8(src);
|
||||
}
|
||||
if (dataSize > 22) {
|
||||
if (sbufBytesRemaining(src) >= 1) {
|
||||
rxConfigMutable()->fpvCamAngleDegrees = sbufReadU8(src);
|
||||
}
|
||||
break;
|
||||
|
|
|
@ -26,14 +26,25 @@
|
|||
#include "drivers/dma.h"
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, TIMER_INPUT_ENABLED), // PPM IN
|
||||
DEF_TIM(TIM16,CH1, PA6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM1
|
||||
DEF_TIM(TIM8, CH1N,PA7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED), // PWM2
|
||||
DEF_TIM(TIM8, CH2, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM3
|
||||
DEF_TIM(TIM17,CH1, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM4
|
||||
DEF_TIM(TIM1, CH2N,PB0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED), // PWM5
|
||||
DEF_TIM(TIM8, CH3N,PB1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED), // PWM6
|
||||
DEF_TIM(TIM2, CH1, PA0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM7
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM8
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_LED, TIMER_OUTPUT_ENABLED), // LED_STRIP --requires resource remap with dshot (remap to motor 5??)--
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_PPM, TIMER_INPUT_ENABLED), // PPM
|
||||
DEF_TIM(TIM16,CH1, PA6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM1 (1,4)
|
||||
DEF_TIM(TIM8, CH1N,PA7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED), // PWM2 (2,3)
|
||||
DEF_TIM(TIM8, CH2, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM3 (2,5)
|
||||
DEF_TIM(TIM17,CH1, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM4 (1,1)
|
||||
|
||||
#ifdef BFF3_USE_HEXA_DSHOT
|
||||
// For HEXA dshot
|
||||
DEF_TIM(TIM1, CH2N,PB0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED), // PWM5 (1,3)
|
||||
DEF_TIM(TIM8, CH3N,PB1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED), // PWM6 (2,1)
|
||||
#else
|
||||
// For softserial
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED), // PWM5 (1,2) !LED
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED), // PWM6 (1,3)
|
||||
#endif
|
||||
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM7/UART2_RX
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED), // PWM8/UART2_TX
|
||||
|
||||
// When using softserial config, LED will have DMA conflict with PB0 (SOFTSERIAL1_RX).
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR | TIM_USE_LED, TIMER_OUTPUT_ENABLED), // LED (1,2)
|
||||
};
|
||||
|
|
|
@ -29,8 +29,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
|||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_PPM, TIMER_INPUT_ENABLED, 0 ), // PPM IN
|
||||
DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1 ), // S1_OUT - DMA1_ST6_CH3
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S2_OUT - DMA1_ST7_CH5
|
||||
DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_INVERTED, 0 ), // S3_OUT - DMA2_ST2_CH0
|
||||
// DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S3_OUT - DMA1_ST2_CH5
|
||||
DEF_TIM(TIM1, CH3N, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_INVERTED, 0 ), // S3_OUT - DMA2_ST6_CH0
|
||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S4_OUT - DMA1_ST1_CH3
|
||||
|
||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0 ), // LED_STRIP - DMA1_ST2_CH6
|
||||
|
|
|
@ -187,4 +187,4 @@
|
|||
#define TARGET_IO_PORTD (BIT(2))
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 6
|
||||
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) )
|
||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) )
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue