1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 00:05:33 +03:00

Rebased onto CMS (WIP, nasty OLEDCMS / cli hang bug)

When OLEDCMS is enabled, enter cli hangs the FC.
This commit is contained in:
jflyper 2016-11-04 01:59:02 +09:00
parent 2bf74e0513
commit 278cf811a7
111 changed files with 2415 additions and 1493 deletions

View file

@ -561,7 +561,7 @@ HIGHEND_SRC = \
flight/gps_conversion.c \
io/gps.c \
io/ledstrip.c \
io/display.c \
io/dashboard.c \
sensors/sonar.c \
sensors/barometer.c \
telemetry/telemetry.c \
@ -734,7 +734,11 @@ OPTIMIZE = -O0
LTO_FLAGS = $(OPTIMIZE)
else
OPTIMIZE = -Os
ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS)))
LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE)
else
LTO_FLAGS = -fuse-linker-plugin $(OPTIMIZE)
endif
endif
DEBUG_FLAGS = -ggdb3 -DDEBUG

View file

@ -75,7 +75,7 @@ void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refresh
const float cs = cosf(omega);
const float alpha = sn / (2 * Q);
float b0, b1, b2, a0, a1, a2;
float b0 = 0, b1 = 0, b2 = 0, a0 = 0, a1 = 0, a2 = 0;
switch (filterType) {
case FILTER_LPF:

View file

@ -56,6 +56,12 @@ void EXTIInit(void)
#if defined(STM32F3) || defined(STM32F4)
/* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
#ifdef REMAP_TIM16_DMA
SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_TIM16, ENABLE);
#endif
#ifdef REMAP_TIM17_DMA
SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_TIM17, ENABLE);
#endif
#endif
memset(extiChannelRecs, 0, sizeof(extiChannelRecs));
memset(extiGroupPriority, 0xff, sizeof(extiGroupPriority));

View file

@ -156,7 +156,7 @@ void pwmCompleteMotorUpdate(uint8_t motorCount)
void motorInit(const motorConfig_t *motorConfig, uint16_t idlePulse, uint8_t motorCount)
{
uint32_t timerMhzCounter;
uint32_t timerMhzCounter = 0;
pwmWriteFuncPtr pwmWritePtr;
bool useUnsyncedPwm = motorConfig->useUnsyncedPwm;
bool isDigital = false;
@ -208,7 +208,7 @@ void motorInit(const motorConfig_t *motorConfig, uint16_t idlePulse, uint8_t mot
break;
}
const timerHardware_t *timerHardware = timerGetByTag(tag, TIMER_OUTPUT_ENABLED);
const timerHardware_t *timerHardware = timerGetByTag(tag, TIM_USE_MOTOR);
if (timerHardware == NULL) {
/* flag failure and disable ability to arm */
@ -271,7 +271,7 @@ void servoInit(const servoConfig_t *servoConfig)
IOInit(servos[servoIndex].io, OWNER_SERVO, RESOURCE_OUTPUT, RESOURCE_INDEX(servoIndex));
IOConfigGPIO(servos[servoIndex].io, IOCFG_AF_PP);
const timerHardware_t *timer = timerGetByTag(tag, TIMER_OUTPUT_ENABLED);
const timerHardware_t *timer = timerGetByTag(tag, TIM_USE_SERVO);
if (timer == NULL) {
/* flag failure and disable ability to arm */

View file

@ -84,7 +84,7 @@ void pwmCompleteDigitalMotorUpdate(uint8_t motorCount)
{
UNUSED(motorCount);
for (uint8_t i = 0; i < dmaMotorTimerCount; i++) {
for (int i = 0; i < dmaMotorTimerCount; i++) {
TIM_SetCounter(dmaMotorTimers[i].timer, 0);
TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
}
@ -123,18 +123,18 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
RCC_ClockCmd(timerRCC(timer), ENABLE);
TIM_Cmd(timer, DISABLE);
uint32_t hz;
switch (pwmProtocolType) {
case(PWM_TYPE_DSHOT600):
hz = MOTOR_DSHOT600_MHZ * 1000000;
break;
case(PWM_TYPE_DSHOT300):
hz = MOTOR_DSHOT300_MHZ * 1000000;
break;
default:
case(PWM_TYPE_DSHOT150):
hz = MOTOR_DSHOT150_MHZ * 1000000;
}
uint32_t hz;
switch (pwmProtocolType) {
case(PWM_TYPE_DSHOT600):
hz = MOTOR_DSHOT600_MHZ * 1000000;
break;
case(PWM_TYPE_DSHOT300):
hz = MOTOR_DSHOT300_MHZ * 1000000;
break;
default:
case(PWM_TYPE_DSHOT150):
hz = MOTOR_DSHOT150_MHZ * 1000000;
}
TIM_TimeBaseStructure.TIM_Prescaler = (uint16_t)((SystemCoreClock / timerClockDivisor(timer) / hz) - 1);
TIM_TimeBaseStructure.TIM_Period = MOTOR_BITLENGTH;
@ -146,20 +146,15 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
TIM_OCStructInit(&TIM_OCInitStructure);
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Disable;
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset;
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCNPolarity_Low;
TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCNPolarity_Low;
TIM_OCInitStructure.TIM_OCNPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPolarity_High : TIM_OCNPolarity_Low;
} else {
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable;
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Reset;
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Set;
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCNPolarity_High;
TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCNPolarity_High;
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
TIM_OCInitStructure.TIM_OCPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCPolarity_Low : TIM_OCPolarity_High;
}
TIM_OCInitStructure.TIM_Pulse = 0;
timerOCInit(timer, timerHardware->channel, &TIM_OCInitStructure);

View file

@ -85,7 +85,7 @@ void pwmCompleteDigitalMotorUpdate(uint8_t motorCount)
{
UNUSED(motorCount);
for (uint8_t i = 0; i < dmaMotorTimerCount; i++) {
for (int i = 0; i < dmaMotorTimerCount; i++) {
TIM_SetCounter(dmaMotorTimers[i].timer, 0);
TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
}
@ -124,18 +124,18 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
RCC_ClockCmd(timerRCC(timer), ENABLE);
TIM_Cmd(timer, DISABLE);
uint32_t hz;
switch (pwmProtocolType) {
case(PWM_TYPE_DSHOT600):
hz = MOTOR_DSHOT600_MHZ * 1000000;
break;
case(PWM_TYPE_DSHOT300):
hz = MOTOR_DSHOT300_MHZ * 1000000;
break;
default:
case(PWM_TYPE_DSHOT150):
hz = MOTOR_DSHOT150_MHZ * 1000000;
}
uint32_t hz;
switch (pwmProtocolType) {
case(PWM_TYPE_DSHOT600):
hz = MOTOR_DSHOT600_MHZ * 1000000;
break;
case(PWM_TYPE_DSHOT300):
hz = MOTOR_DSHOT300_MHZ * 1000000;
break;
default:
case(PWM_TYPE_DSHOT150):
hz = MOTOR_DSHOT150_MHZ * 1000000;
}
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / timerClockDivisor(timer) / hz) - 1;
TIM_TimeBaseStructure.TIM_Period = MOTOR_BITLENGTH;
@ -145,12 +145,15 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
}
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Reset;
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Set;
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCNPolarity_High;
TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCNPolarity_High;
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable;
if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset;
TIM_OCInitStructure.TIM_OCNPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPolarity_High : TIM_OCNPolarity_Low;
} else {
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
TIM_OCInitStructure.TIM_OCPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCPolarity_Low : TIM_OCPolarity_High;
}
TIM_OCInitStructure.TIM_Pulse = 0;
timerOCInit(timer, timerHardware->channel, &TIM_OCInitStructure);

View file

@ -393,7 +393,7 @@ void pwmRxInit(const pwmConfig_t *pwmConfig)
pwmInputPort_t *port = &pwmInputPorts[channel];
const timerHardware_t *timer = timerGetByTag(pwmConfig->ioTags[channel], TIMER_INPUT_ENABLED);
const timerHardware_t *timer = timerGetByTag(pwmConfig->ioTags[channel], TIM_USE_PWM);
if (!timer) {
/* TODO: maybe fail here if not enough channels? */
@ -408,7 +408,7 @@ void pwmRxInit(const pwmConfig_t *pwmConfig)
IO_t io = IOGetByTag(pwmConfig->ioTags[channel]);
IOInit(io, OWNER_PWMINPUT, RESOURCE_INPUT, RESOURCE_INDEX(channel));
IOConfigGPIO(io, timer->ioMode);
IOConfigGPIO(io, IOCFG_IPD);
#if defined(USE_HAL_DRIVER)
pwmICConfig(timer->tim, timer->channel, TIM_ICPOLARITY_RISING);
@ -459,7 +459,7 @@ void ppmRxInit(const ppmConfig_t *ppmConfig, uint8_t pwmProtocol)
pwmInputPort_t *port = &pwmInputPorts[FIRST_PWM_PORT];
const timerHardware_t *timer = timerGetByTag(ppmConfig->ioTag, TIMER_INPUT_ENABLED);
const timerHardware_t *timer = timerGetByTag(ppmConfig->ioTag, TIM_USE_PPM);
if (!timer) {
/* TODO: fail here? */
return;
@ -472,7 +472,7 @@ void ppmRxInit(const ppmConfig_t *ppmConfig, uint8_t pwmProtocol)
IO_t io = IOGetByTag(ppmConfig->ioTag);
IOInit(io, OWNER_PPMINPUT, RESOURCE_INPUT, 0);
IOConfigGPIO(io, timer->ioMode);
IOConfigGPIO(io, IOCFG_IPD);
#if defined(USE_HAL_DRIVER)
pwmICConfig(timer->tim, timer->channel, TIM_ICPOLARITY_RISING);

View file

@ -199,7 +199,7 @@ static inline uint8_t lookupChannelIndex(const uint16_t channel)
rccPeriphTag_t timerRCC(TIM_TypeDef *tim)
{
for (uint8_t i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
if (timerDefinitions[i].TIMx == tim) {
return timerDefinitions[i].rcc;
}
@ -686,14 +686,14 @@ void timerInit(void)
#endif
/* enable the timer peripherals */
for (uint8_t i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
RCC_ClockCmd(timerRCC(timerHardware[i].tim), ENABLE);
}
#if defined(STM32F3) || defined(STM32F4)
for (uint8_t timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
for (int timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
IOConfigGPIOAF(IOGetByTag(timerHardwarePtr->tag), timerHardwarePtr->ioMode, timerHardwarePtr->alternateFunction);
IOConfigGPIOAF(IOGetByTag(timerHardwarePtr->tag), IOCFG_AF_PP, timerHardwarePtr->alternateFunction);
}
#endif
@ -755,14 +755,11 @@ void timerForceOverflow(TIM_TypeDef *tim)
}
}
const timerHardware_t *timerGetByTag(ioTag_t tag, timerFlag_e flag)
const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag)
{
for (uint8_t i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
if (timerHardware[i].tag == tag) {
if (flag && (timerHardware[i].output & flag) == flag) {
return &timerHardware[i];
} else if (!flag && timerHardware[i].output == flag) {
// TODO: shift flag by one so not to be 0
if (timerHardware[i].usageFlags & flag) {
return &timerHardware[i];
}
}

View file

@ -54,6 +54,13 @@ typedef uint32_t timCNT_t;
#error "Unknown CPU defined"
#endif
typedef enum {
TIM_USE_PPM = 0x1,
TIM_USE_PWM = 0x2,
TIM_USE_MOTOR = 0x4,
TIM_USE_SERVO = 0x8,
TIM_USE_LED = 0x10
} timerUsageFlag_e;
// use different types from capture and overflow - multiple overflow handlers are implemented as linked list
struct timerCCHandlerRec_s;
@ -80,8 +87,8 @@ typedef struct timerHardware_s {
ioTag_t tag;
uint8_t channel;
uint8_t irq;
timerUsageFlag_e usageFlags;
uint8_t output;
ioConfig_t ioMode;
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
uint8_t alternateFunction;
#endif
@ -171,7 +178,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz); // TODO -
rccPeriphTag_t timerRCC(TIM_TypeDef *tim);
const timerHardware_t *timerGetByTag(ioTag_t tag, timerFlag_e flag);
const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag);
#if defined(USE_HAL_DRIVER)
TIM_HandleTypeDef* timerFindTimerHandle(TIM_TypeDef *tim);

View file

@ -208,7 +208,7 @@ static inline uint8_t lookupChannelIndex(const uint16_t channel)
rccPeriphTag_t timerRCC(TIM_TypeDef *tim)
{
for (uint8_t i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
for (int i = 0; i < HARDWARE_TIMER_DEFINITION_COUNT; i++) {
if (timerDefinitions[i].TIMx == tim) {
return timerDefinitions[i].rcc;
}
@ -787,14 +787,14 @@ void timerInit(void)
#endif
/* enable the timer peripherals */
for (uint8_t i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
RCC_ClockCmd(timerRCC(timerHardware[i].tim), ENABLE);
}
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
for (uint8_t timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
for (int timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
IOConfigGPIOAF(IOGetByTag(timerHardwarePtr->tag), timerHardwarePtr->ioMode, timerHardwarePtr->alternateFunction);
IOConfigGPIOAF(IOGetByTag(timerHardwarePtr->tag), IOCFG_AF_PP, timerHardwarePtr->alternateFunction);
}
#endif
@ -856,14 +856,11 @@ void timerForceOverflow(TIM_TypeDef *tim)
}
}
const timerHardware_t *timerGetByTag(ioTag_t tag, timerFlag_e flag)
const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag)
{
for (uint8_t i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
if (timerHardware[i].tag == tag) {
if (flag && (timerHardware[i].output & flag) == flag) {
return &timerHardware[i];
} else if (!flag && timerHardware[i].output == flag) {
// TODO: shift flag by one so not to be 0
if (timerHardware[i].output & flag) {
return &timerHardware[i];
}
}

View file

@ -244,6 +244,14 @@ void resetServoConfig(servoConfig_t *servoConfig)
{
servoConfig->servoCenterPulse = 1500;
servoConfig->servoPwmRate = 50;
int servoIndex = 0;
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && servoIndex < MAX_SUPPORTED_SERVOS; i++) {
if (timerHardware[i].usageFlags & TIM_USE_SERVO) {
servoConfig->ioTags[servoIndex] = timerHardware[i].tag;
servoIndex++;
}
}
}
#endif
@ -263,9 +271,9 @@ void resetMotorConfig(motorConfig_t *motorConfig)
motorConfig->mincommand = 1000;
motorConfig->digitalIdleOffset = 40;
uint8_t motorIndex = 0;
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && i < MAX_SUPPORTED_MOTORS; i++) {
if ((timerHardware[i].output & TIMER_OUTPUT_ENABLED) == TIMER_OUTPUT_ENABLED) {
int motorIndex = 0;
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && motorIndex < MAX_SUPPORTED_MOTORS; i++) {
if (timerHardware[i].usageFlags & TIM_USE_MOTOR) {
motorConfig->ioTags[motorIndex] = timerHardware[i].tag;
motorIndex++;
}
@ -305,7 +313,7 @@ void resetPpmConfig(ppmConfig_t *ppmConfig)
ppmConfig->ioTag = IO_TAG(PPM_PIN);
#else
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
if ((timerHardware[i].output == TIMER_INPUT_ENABLED)) {
if (timerHardware[i].usageFlags & TIM_USE_PPM) {
ppmConfig->ioTag = timerHardware[i].tag;
return;
}
@ -317,9 +325,9 @@ void resetPpmConfig(ppmConfig_t *ppmConfig)
void resetPwmConfig(pwmConfig_t *pwmConfig)
{
uint8_t inputIndex = 0;
int inputIndex = 0;
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && inputIndex < PWM_INPUT_PORT_COUNT; i++) {
if ((timerHardware[i].output == TIMER_INPUT_ENABLED)) {
if (timerHardware[i].usageFlags & TIM_USE_PWM) {
pwmConfig->ioTags[inputIndex] = timerHardware[i].tag;
inputIndex++;
}
@ -900,8 +908,8 @@ void validateAndFixConfig(void)
#endif
#if defined(CC3D) && defined(DISPLAY) && defined(USE_UART3)
if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DISPLAY)) {
featureClear(FEATURE_DISPLAY);
if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DASHBOARD)) {
featureClear(FEATURE_DASHBOARD);
}
#endif

View file

@ -45,7 +45,7 @@ typedef enum {
FEATURE_RX_MSP = 1 << 14,
FEATURE_RSSI_ADC = 1 << 15,
FEATURE_LED_STRIP = 1 << 16,
FEATURE_DISPLAY = 1 << 17,
FEATURE_DASHBOARD = 1 << 17,
FEATURE_OSD = 1 << 18,
FEATURE_BLACKBOX = 1 << 19,
FEATURE_CHANNEL_FORWARDING = 1 << 20,

View file

@ -1778,17 +1778,3 @@ void mspFcInit(void)
{
initActiveBoxIds();
}
void mspServerPush(mspPacket_t *push, uint8_t *data, int len)
{
sbuf_t *dst = &push->buf;
while (len--) {
sbufWriteU8(dst, *data++);
}
}
mspPushCommandFnPtr mspFcPushInit(void)
{
return mspServerPush;
}

View file

@ -21,5 +21,3 @@
void mspFcInit(void);
mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn);
mspPushCommandFnPtr mspFcPushInit(void);

View file

@ -41,9 +41,10 @@
#include "flight/altitudehold.h"
#include "io/cms.h"
#include "io/cms_types.h"
#include "io/beeper.h"
#include "io/display.h"
#include "io/dashboard.h"
#include "io/gps.h"
#include "io/ledstrip.h"
#include "io/osd.h"
@ -225,11 +226,11 @@ static void taskCalculateAltitude(uint32_t currentTime)
}}
#endif
#ifdef DISPLAY
static void taskUpdateDisplay(uint32_t currentTime)
#ifdef USE_DASHBOARD
static void taskUpdateDashboard(uint32_t currentTime)
{
if (feature(FEATURE_DISPLAY)) {
displayUpdate(currentTime);
if (feature(FEATURE_DASHBOARD)) {
dashboardUpdate(currentTime);
}
}
#endif
@ -323,8 +324,8 @@ void fcTasksInit(void)
#if defined(BARO) || defined(SONAR)
setTaskEnabled(TASK_ALTITUDE, sensors(SENSOR_BARO) || sensors(SENSOR_SONAR));
#endif
#ifdef DISPLAY
setTaskEnabled(TASK_DISPLAY, feature(FEATURE_DISPLAY));
#ifdef USE_DASHBOARD
setTaskEnabled(TASK_DASHBOARD, feature(FEATURE_DASHBOARD));
#endif
#ifdef TELEMETRY
setTaskEnabled(TASK_TELEMETRY, feature(FEATURE_TELEMETRY));
@ -469,10 +470,10 @@ cfTask_t cfTasks[TASK_COUNT] = {
},
#endif
#ifdef DISPLAY
[TASK_DISPLAY] = {
.taskName = "DISPLAY",
.taskFunc = taskUpdateDisplay,
#ifdef USE_DASHBOARD
[TASK_DASHBOARD] = {
.taskName = "DASHBOARD",
.taskFunc = taskUpdateDashboard,
.desiredPeriod = 1000000 / 10,
.staticPriority = TASK_PRIORITY_LOW,
},

View file

@ -46,7 +46,7 @@
#include "io/beeper.h"
#include "io/motors.h"
#include "io/vtx.h"
#include "io/display.h"
#include "io/dashboard.h"
#include "sensors/barometer.h"
#include "sensors/battery.h"
@ -293,13 +293,13 @@ void processRcStickPositions(rxConfig_t *rxConfig, throttleStatus_e throttleStat
return;
}
#ifdef DISPLAY
#ifdef USE_DASHBOARD
if (rcSticks == THR_LO + YAW_CE + PIT_HI + ROL_LO) {
displayDisablePageCycling();
dashboardDisablePageCycling();
}
if (rcSticks == THR_LO + YAW_CE + PIT_HI + ROL_HI) {
displayEnablePageCycling();
dashboardEnablePageCycling();
}
#endif

View file

@ -9,6 +9,8 @@
#ifdef CANVAS
#include "common/utils.h"
#include "drivers/system.h"
#include "io/cms.h"
@ -67,28 +69,36 @@ int canvasWrite(uint8_t col, uint8_t row, char *string)
return canvasOutput(MSP_CANVAS, (uint8_t *)buf, len + 4);
}
screenFnVTable_t canvasVTable = {
void canvasResync(displayPort_t *pPort)
{
pPort->rows = 13; // XXX Will reflect NTSC/PAL in the future
pPort->rows = 30;
}
uint32_t canvasTxBytesFree(void)
{
return mspSerialTxBytesFree();
}
displayPortVTable_t canvasVTable = {
canvasBegin,
canvasEnd,
canvasClear,
canvasWrite,
canvasHeartBeat,
NULL,
canvasResync,
canvasTxBytesFree,
};
void canvasCmsInit(displayPort_t *pPort)
{
pPort->rows = 13;
pPort->rows = 13; // XXX Will reflect NTSC/PAL in the future
pPort->cols = 30;
pPort->buftime = 23; // = 256/(115200/10)
pPort->bufsize = 192; // 256 * 3/4 (Be conservative)
pPort->VTable = &canvasVTable;
pPort->vTable = &canvasVTable;
}
void canvasInit()
{
mspSerialPushInit(mspFcPushInit()); // Called once at startup to initialize push function in msp
cmsDeviceRegister(canvasCmsInit);
}
#endif

View file

@ -1,3 +1,3 @@
#pragma once
void canvasInit(void);
void canvasCmsInit(displayPort_t *);
void canvasCmsInit(displayPort_t *dPort);

View file

@ -37,13 +37,22 @@
#include "io/cms.h"
#include "io/cms_types.h"
#ifdef CANVAS
#include "io/canvas.h"
#endif
#ifdef USE_FLASHFS
#include "io/flashfs.h"
#endif
#ifdef OSD
#include "io/osd.h"
#include "io/display.h"
#endif
#ifdef USE_DASHBOARD
#include "io/dashboard.h"
#endif
#include "fc/config.h"
#include "fc/rc_controls.h"
@ -55,10 +64,26 @@
#include "config/config_master.h"
#include "config/feature.h"
#include "io/cms.h"
#include "build/debug.h"
// External menu contents
#include "io/cms_imu.h"
#include "io/cms_blackbox.h"
#include "io/cms_vtx.h"
#ifdef OSD
#include "io/cms_osd.h"
#endif // OSD
#include "io/cms_ledstrip.h"
#ifdef VTX_SMARTAUDIO
#include "io/vtx_smartaudio.h"
#endif
// Forwards
void cmsx_InfoInit(void);
void cmsx_FeatureRead(void);
void cmsx_FeatureWriteback(void);
// Device management
#define CMS_MAX_DEVICE 4
@ -107,37 +132,40 @@ int8_t lastCursorPos;
void cmsScreenClear(displayPort_t *instance)
{
instance->VTable->clear();
instance->vTable->clear();
instance->cleared = true;
lastCursorPos = -1; // XXX Here
}
void cmsScreenBegin(displayPort_t *instance)
{
instance->VTable->begin();
instance->VTable->clear();
instance->vTable->begin();
instance->vTable->clear();
}
void cmsScreenEnd(displayPort_t *instance)
{
instance->VTable->end();
instance->vTable->end();
}
int cmsScreenWrite(displayPort_t *instance, uint8_t x, uint8_t y, char *s)
{
return instance->VTable->write(x, y, s);
return instance->vTable->write(x, y, s);
}
void cmsScreenHeartBeat(displayPort_t *instance)
{
if (instance->VTable->heartbeat)
instance->VTable->heartbeat();
instance->vTable->heartbeat();
}
void cmsScreenResync(displayPort_t *instance)
{
if (instance->VTable->resync)
instance->VTable->resync();
instance->vTable->resync(instance);
}
uint16_t cmsScreenTxBytesFree(displayPort_t *instance)
{
return instance->vTable->txBytesFree();
}
void cmsScreenInit(displayPort_t *pDisp, cmsDeviceInitFuncPtr cmsDeviceInitFunc)
@ -163,9 +191,11 @@ void cmsScreenInit(displayPort_t *pDisp, cmsDeviceInitFuncPtr cmsDeviceInitFunc)
//
#define LEFT_MENU_COLUMN 1
#define RIGHT_MENU_COLUMN(p) ((p)->cols - 7)
#define RIGHT_MENU_COLUMN(p) ((p)->cols - 8)
#define MAX_MENU_ITEMS(p) ((p)->rows - 2)
displayPort_t currentDisplay;
bool cmsInMenu = false;
OSD_Entry *menuStack[10]; //tab to save menu stack
@ -209,7 +239,7 @@ void cmsUpdateMaxRows(displayPort_t *instance)
currentMenuIdx--;
}
static void cmsFtoa(int32_t value, char *floatString)
static void cmsFormatFloat(int32_t value, char *floatString)
{
uint8_t k;
// np. 3450
@ -224,7 +254,8 @@ static void cmsFtoa(int32_t value, char *floatString)
// 03.450
// usuwam koncowe zera i kropke
for (k = 5; k > 1; k--)
// Keep the first decimal place
for (k = 5; k > 3; k--)
if (floatString[k] == '0' || floatString[k] == '.')
floatString[k] = 0;
else
@ -257,6 +288,12 @@ int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row, bool dr
int cnt = 0;
switch (p->type) {
case OME_String:
if (IS_PRINTVALUE(p) && p->data) {
cnt = cmsScreenWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, p->data);
CLR_PRINTVALUE(p);
}
break;
case OME_Submenu:
if (IS_PRINTVALUE(p)) {
cnt = cmsScreenWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, ">");
@ -282,8 +319,8 @@ int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row, bool dr
}
break;
}
case OME_VISIBLE:
#ifdef OSD
case OME_VISIBLE:
if (IS_PRINTVALUE(p) && p->data) {
uint32_t address = (uint32_t)p->data;
uint16_t *val;
@ -297,8 +334,8 @@ int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row, bool dr
}
CLR_PRINTVALUE(p);
}
#endif
break;
#endif
case OME_UINT8:
if (IS_PRINTVALUE(p) && p->data) {
OSD_UINT8_t *ptr = p->data;
@ -348,7 +385,7 @@ int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row, bool dr
case OME_FLOAT:
if (IS_PRINTVALUE(p) && p->data) {
OSD_FLOAT_t *ptr = p->data;
cmsFtoa(*ptr->val * ptr->multipler, buff);
cmsFormatFloat(*ptr->val * ptr->multipler, buff);
cmsPad(buff, 5);
cnt = cmsScreenWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay) - 1, row, buff); // XXX One char left ???
CLR_PRINTVALUE(p);
@ -364,10 +401,8 @@ int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row, bool dr
return cnt;
}
void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTime)
void cmsDrawMenu(displayPort_t *pDisplay)
{
UNUSED(currentTime);
uint8_t i;
OSD_Entry *p;
uint8_t top = (pDisplay->rows - currentMenuIdx) / 2 - 1;
@ -377,7 +412,7 @@ void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTime)
static uint8_t pollDenom = 0;
bool drawPolled = (++pollDenom % 8 == 0);
int16_t cnt = 0;
uint32_t room = cmsScreenTxBytesFree(pDisplay);
if (!currentMenu)
return;
@ -404,20 +439,26 @@ void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTime)
currentCursorPos++;
if (lastCursorPos >= 0 && currentCursorPos != lastCursorPos) {
cnt += cmsScreenWrite(pDisplay, LEFT_MENU_COLUMN, lastCursorPos + top, " ");
room -= cmsScreenWrite(pDisplay, LEFT_MENU_COLUMN, lastCursorPos + top, " ");
}
if (room < 30)
return;
if (lastCursorPos != currentCursorPos) {
cnt += cmsScreenWrite(pDisplay, LEFT_MENU_COLUMN, currentCursorPos + top, " >");
room -= cmsScreenWrite(pDisplay, LEFT_MENU_COLUMN, currentCursorPos + top, " >");
lastCursorPos = currentCursorPos;
}
if (room < 30)
return;
// Print text labels
for (i = 0, p = currentMenu; i < MAX_MENU_ITEMS(pDisplay) && p->type != OME_END; i++, p++) {
if (IS_PRINTLABEL(p)) {
cnt += cmsScreenWrite(pDisplay, LEFT_MENU_COLUMN + 2, i + top, p->text);
room -= cmsScreenWrite(pDisplay, LEFT_MENU_COLUMN + 2, i + top, p->text);
CLR_PRINTLABEL(p);
if (cnt > pDisplay->batchsize)
if (room < 30)
return;
}
}
@ -425,33 +466,25 @@ void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTime)
// Print values
// XXX Polled values at latter positions in the list may not be
// XXX printed if the cnt exceeds batchsize in the middle of the list.
// XXX printed if not enough room in the middle of the list.
for (i = 0, p = currentMenu; i < MAX_MENU_ITEMS(pDisplay) && p->type != OME_END; i++, p++) {
if (IS_PRINTVALUE(p)) {
cnt += cmsDrawMenuEntry(pDisplay, p, top + i, drawPolled);
if (cnt > pDisplay->batchsize)
room -= cmsDrawMenuEntry(pDisplay, p, top + i, drawPolled);
if (room < 30)
return;
}
}
}
// XXX Needs separation
OSD_Entry menuPid[];
void cmsx_PidRead(void);
void cmsx_PidWriteback(void);
OSD_Entry menuRateExpo[];
void cmsx_RateExpoRead(void);
void cmsx_RateExpoWriteback(void);
long cmsMenuChange(displayPort_t *pDisplay, void *ptr)
{
if (ptr) {
// XXX (jflyper): This can be avoided by adding pre- and post-
// XXX (or onEnter and onExit) functions?
if (ptr == &menuPid[0])
if (ptr == cmsx_menuPid)
cmsx_PidRead();
if (ptr == &menuRateExpo[0])
if (ptr == cmsx_menuRateExpo)
cmsx_RateExpoRead();
if ((OSD_Entry *)ptr != currentMenu) {
@ -474,11 +507,11 @@ long cmsMenuBack(displayPort_t *pDisplay)
{
// becasue pids and rates may be stored in profiles we need some thicks to manipulate it
// hack to save pid profile
if (currentMenu == &menuPid[0])
if (currentMenu == cmsx_menuPid)
cmsx_PidWriteback();
// hack - save rate config for current profile
if (currentMenu == &menuRateExpo[0])
if (currentMenu == cmsx_menuRateExpo)
cmsx_RateExpoWriteback();
if (menuStackIdx) {
@ -494,19 +527,6 @@ long cmsMenuBack(displayPort_t *pDisplay)
return 0;
}
// XXX This should go to device
void cmsComputeBatchsize(displayPort_t *pDisplay)
{
pDisplay->batchsize = (pDisplay->buftime < CMS_UPDATE_INTERVAL) ? pDisplay->bufsize : (pDisplay->bufsize * CMS_UPDATE_INTERVAL) / pDisplay->buftime;
}
// XXX Separation
void cmsx_FeatureRead(void);
void cmsx_FeatureWriteback(void);
void cmsx_InfoInit(void);
displayPort_t currentDisplay;
void cmsMenuOpen(void)
{
cmsDeviceInitFuncPtr initfunc;
@ -528,7 +548,6 @@ void cmsMenuOpen(void)
return;
cmsScreenInit(&currentDisplay, initfunc);
cmsComputeBatchsize(&currentDisplay);
cmsScreenBegin(&currentDisplay);
cmsMenuChange(&currentDisplay, currentMenu);
}
@ -640,8 +659,8 @@ uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
SET_PRINTVALUE(p);
}
break;
case OME_VISIBLE:
#ifdef OSD
case OME_VISIBLE:
if (p->data) {
uint32_t address = (uint32_t)p->data;
uint16_t *val;
@ -654,8 +673,8 @@ uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
*val %= ~VISIBLE_FLAG;
SET_PRINTVALUE(p);
}
#endif
break;
#endif
case OME_UINT8:
case OME_FLOAT:
if (p->data) {
@ -730,6 +749,8 @@ uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
SET_PRINTVALUE(p);
}
break;
case OME_String:
break;
case OME_Poll_INT16:
case OME_Label:
case OME_END:
@ -738,8 +759,6 @@ uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
return res;
}
OSD_Entry menuRc[];
void cmsUpdate(displayPort_t *pDisplay, uint32_t currentTime)
{
static int16_t rcDelay = BUTTON_TIME;
@ -779,7 +798,7 @@ void cmsUpdate(displayPort_t *pDisplay, uint32_t currentTime)
key = KEY_RIGHT;
rcDelay = BUTTON_TIME;
}
else if ((IS_HI(YAW) || IS_LO(YAW)) && currentMenu != menuRc) // this menu is used to check transmitter signals so can't exit using YAW
else if ((IS_HI(YAW) || IS_LO(YAW)) && currentMenu != cmsx_menuRc) // this menu is used to check transmitter signals so can't exit using YAW
{
key = KEY_ESC;
rcDelay = BUTTON_TIME;
@ -792,7 +811,7 @@ void cmsUpdate(displayPort_t *pDisplay, uint32_t currentTime)
return;
}
cmsDrawMenu(pDisplay, currentTime);
cmsDrawMenu(pDisplay);
if (currentTime > lastCmsHeartBeat + 500) {
// Heart beat for external CMS display device @ 500msec
@ -804,15 +823,13 @@ void cmsUpdate(displayPort_t *pDisplay, uint32_t currentTime)
lastCalled = currentTime;
}
void cmsHandler(uint32_t unusedTime)
void cmsHandler(uint32_t currentTime)
{
UNUSED(unusedTime);
if (cmsDeviceCount < 0)
return;
static uint32_t lastCalled = 0;
uint32_t now = millis();
const uint32_t now = currentTime / 1000;
if (now - lastCalled >= CMS_UPDATE_INTERVAL) {
cmsUpdate(&currentDisplay, now);
@ -826,269 +843,37 @@ void cmsInit(void)
}
//
// Menu tables, should eventually be all GONE!?
// Menu contents
//
//
// IMU
//
// Info
OSD_UINT8_t entryPidProfile = {&masterConfig.current_profile_index, 0, MAX_PROFILE_COUNT, 1};
static char infoGitRev[GIT_SHORT_REVISION_LENGTH];
static char infoTargetName[] = __TARGET__;
uint8_t tempPid[4][3];
#include "msp/msp_protocol.h" // XXX for FC identification... not available elsewhere
static OSD_UINT8_t entryRollP = {&tempPid[PIDROLL][0], 10, 150, 1};
static OSD_UINT8_t entryRollI = {&tempPid[PIDROLL][1], 1, 150, 1};
static OSD_UINT8_t entryRollD = {&tempPid[PIDROLL][2], 0, 150, 1};
OSD_Entry menuInfo[] = {
{ "--- INFO ---", OME_Label, NULL, NULL, 0 },
{ "FWID", OME_String, NULL, BETAFLIGHT_IDENTIFIER, 0 },
{ "FWVER", OME_String, NULL, FC_VERSION_STRING, 0 },
{ "GITREV", OME_String, NULL, infoGitRev, 0 },
{ "TARGET", OME_String, NULL, infoTargetName, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
static OSD_UINT8_t entryPitchP = {&tempPid[PIDPITCH][0], 10, 150, 1};
static OSD_UINT8_t entryPitchI = {&tempPid[PIDPITCH][1], 1, 150, 1};
static OSD_UINT8_t entryPitchD = {&tempPid[PIDPITCH][2], 0, 150, 1};
static OSD_UINT8_t entryYawP = {&tempPid[PIDYAW][0], 10, 150, 1};
static OSD_UINT8_t entryYawI = {&tempPid[PIDYAW][1], 1, 150, 1};
static OSD_UINT8_t entryYawD = {&tempPid[PIDYAW][2], 0, 150, 1};
void cmsx_PidRead(void)
void cmsx_InfoInit(void)
{
uint8_t i;
for (i = 0; i < 3; i++) {
tempPid[i][0] = masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[i];
tempPid[i][1] = masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[i];
tempPid[i][2] = masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[i];
for (int i = 0 ; i < GIT_SHORT_REVISION_LENGTH ; i++) {
if (shortGitRevision[i] >= 'a' && shortGitRevision[i] <= 'f')
infoGitRev[i] = shortGitRevision[i] - 'a' + 'A';
else
infoGitRev[i] = shortGitRevision[i];
}
tempPid[3][0] = masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDLEVEL];
tempPid[3][1] = masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDLEVEL];
tempPid[3][2] = masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDLEVEL];
}
void cmsx_PidWriteback(void)
{
uint8_t i;
for (i = 0; i < 3; i++) {
masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[i] = tempPid[i][0];
masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[i] = tempPid[i][1];
masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[i] = tempPid[i][2];
}
masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDLEVEL] = tempPid[3][0];
masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDLEVEL] = tempPid[3][1];
masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDLEVEL] = tempPid[3][2];
}
OSD_Entry menuPid[] =
{
{"--- PID ---", OME_Label, NULL, NULL, 0},
{"ROLL P", OME_UINT8, NULL, &entryRollP, 0},
{"ROLL I", OME_UINT8, NULL, &entryRollI, 0},
{"ROLL D", OME_UINT8, NULL, &entryRollD, 0},
{"PITCH P", OME_UINT8, NULL, &entryPitchP, 0},
{"PITCH I", OME_UINT8, NULL, &entryPitchI, 0},
{"PITCH D", OME_UINT8, NULL, &entryPitchD, 0},
{"YAW P", OME_UINT8, NULL, &entryYawP, 0},
{"YAW I", OME_UINT8, NULL, &entryYawI, 0},
{"YAW D", OME_UINT8, NULL, &entryYawD, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
//
// Rate & Expo
//
controlRateConfig_t rateProfile;
static OSD_FLOAT_t entryRollRate = {&rateProfile.rates[0], 0, 250, 1, 10};
static OSD_FLOAT_t entryPitchRate = {&rateProfile.rates[1], 0, 250, 1, 10};
static OSD_FLOAT_t entryYawRate = {&rateProfile.rates[2], 0, 250, 1, 10};
static OSD_FLOAT_t entryRcRate = {&rateProfile.rcRate8, 0, 200, 1, 10};
static OSD_FLOAT_t entryRcYawRate = {&rateProfile.rcYawRate8, 0, 200, 1, 10};
static OSD_FLOAT_t entryRcExpo = {&rateProfile.rcExpo8, 0, 100, 1, 10};
static OSD_FLOAT_t entryRcExpoYaw = {&rateProfile.rcYawExpo8, 0, 100, 1, 10};
static OSD_FLOAT_t extryTpaEntry = {&rateProfile.dynThrPID, 0, 70, 1, 10};
static OSD_UINT16_t entryTpaBreak = {&rateProfile.tpa_breakpoint, 1100, 1800, 10};
static OSD_FLOAT_t entryPSetpoint = {&masterConfig.profile[0].pidProfile.setpointRelaxRatio, 0, 100, 1, 10};
static OSD_FLOAT_t entryDSetpoint = {&masterConfig.profile[0].pidProfile.dtermSetpointWeight, 0, 255, 1, 10};
void cmsx_RateExpoRead()
{
memcpy(&rateProfile, &masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile], sizeof(controlRateConfig_t));
}
void cmsx_RateExpoWriteback()
{
memcpy(&masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile], &rateProfile, sizeof(controlRateConfig_t));
}
OSD_Entry menuRateExpo[] =
{
{"--- RATE&EXPO ---", OME_Label, NULL, NULL, 0},
{"RC RATE", OME_FLOAT, NULL, &entryRcYawRate, 0},
{"RC YAW RATE", OME_FLOAT, NULL, &entryRcRate, 0},
{"ROLL SUPER", OME_FLOAT, NULL, &entryRollRate, 0},
{"PITCH SUPER", OME_FLOAT, NULL, &entryPitchRate, 0},
{"YAW SUPER", OME_FLOAT, NULL, &entryYawRate, 0},
{"RC EXPO", OME_FLOAT, NULL, &entryRcExpo, 0},
{"RC YAW EXPO", OME_FLOAT, NULL, &entryRcExpoYaw, 0},
{"THR PID ATT", OME_FLOAT, NULL, &extryTpaEntry, 0},
{"TPA BRKPT", OME_UINT16, NULL, &entryTpaBreak, 0},
{"D SETPT", OME_FLOAT, NULL, &entryDSetpoint, 0},
{"D SETPT TRN", OME_FLOAT, NULL, &entryPSetpoint, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
//
// RC preview
//
static OSD_INT16_t entryRcRoll = {&rcData[ROLL], 1, 2500, 0};
static OSD_INT16_t entryRcPitch = {&rcData[PITCH], 1, 2500, 0};
static OSD_INT16_t entryRcThr = {&rcData[THROTTLE], 1, 2500, 0};
static OSD_INT16_t entryRcYaw = {&rcData[YAW], 1, 2500, 0};
static OSD_INT16_t entryRcAux1 = {&rcData[AUX1], 1, 2500, 0};
static OSD_INT16_t entryRcAux2 = {&rcData[AUX2], 1, 2500, 0};
static OSD_INT16_t entryRcAux3 = {&rcData[AUX3], 1, 2500, 0};
static OSD_INT16_t entryRcAux4 = {&rcData[AUX4], 1, 2500, 0};
OSD_Entry menuRc[] =
{
{"--- RC PREV ---", OME_Label, NULL, NULL, 0},
{"ROLL", OME_Poll_INT16, NULL, &entryRcRoll, 0},
{"PITCH", OME_Poll_INT16, NULL, &entryRcPitch, 0},
{"THR", OME_Poll_INT16, NULL, &entryRcThr, 0},
{"YAW", OME_Poll_INT16, NULL, &entryRcYaw, 0},
{"AUX1", OME_Poll_INT16, NULL, &entryRcAux1, 0},
{"AUX2", OME_Poll_INT16, NULL, &entryRcAux2, 0},
{"AUX3", OME_Poll_INT16, NULL, &entryRcAux3, 0},
{"AUX4", OME_Poll_INT16, NULL, &entryRcAux4, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
//
// Misc
//
OSD_UINT16_t entryMinThrottle = {&masterConfig.motorConfig.minthrottle, 1020, 1300, 10};
OSD_UINT8_t entryGyroSoftLpfHz = {&masterConfig.gyro_soft_lpf_hz, 0, 255, 1};
OSD_UINT16_t entryDtermLpf = {&masterConfig.profile[0].pidProfile.dterm_lpf_hz, 0, 500, 5};
OSD_UINT16_t entryYawLpf = {&masterConfig.profile[0].pidProfile.yaw_lpf_hz, 0, 500, 5};
OSD_UINT16_t entryYawPLimit = {&masterConfig.profile[0].pidProfile.yaw_p_limit, 100, 500, 5};
OSD_UINT8_t entryVbatScale = {&masterConfig.batteryConfig.vbatscale, 1, 250, 1};
OSD_UINT8_t entryVbatMaxCell = {&masterConfig.batteryConfig.vbatmaxcellvoltage, 10, 50, 1};
OSD_Entry menuMisc[]=
{
{"--- MISC ---", OME_Label, NULL, NULL, 0},
{"GYRO LPF", OME_UINT8, NULL, &entryGyroSoftLpfHz, 0},
{"DTERM LPF", OME_UINT16, NULL, &entryDtermLpf, 0},
{"YAW LPF", OME_UINT16, NULL, &entryYawLpf, 0},
{"YAW P LIM", OME_UINT16, NULL, &entryYawPLimit, 0},
{"MIN THR", OME_UINT16, NULL, &entryMinThrottle, 0},
{"VBAT SCALE", OME_UINT8, NULL, &entryVbatScale, 0},
{"VBAT CLMAX", OME_UINT8, NULL, &entryVbatMaxCell, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
OSD_Entry menuImu[] =
{
{"--- CFG. IMU ---", OME_Label, NULL, NULL, 0},
{"PID PROF", OME_UINT8, NULL, &entryPidProfile, 0},
{"PID", OME_Submenu, cmsMenuChange, &menuPid[0], 0},
{"RATE&RXPO", OME_Submenu, cmsMenuChange, &menuRateExpo[0], 0},
{"RC PREV", OME_Submenu, cmsMenuChange, &menuRc[0], 0},
{"MISC", OME_Submenu, cmsMenuChange, &menuMisc[0], 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
//
// Black box
//
//
// Should goto flashfs eventually.
//
#ifdef USE_FLASHFS
void cmsx_EraseFlash(displayPort_t *pDisplay, void *ptr)
{
UNUSED(ptr);
cmsScreenClear(pDisplay);
cmsScreenWrite(pDisplay, 5, 3, "ERASING FLASH...");
cmsScreenResync(pDisplay); // Was max7456RefreshAll(); Why at this timing?
flashfsEraseCompletely();
while (!flashfsIsReady()) {
delay(100);
}
cmsScreenClear(pDisplay);
cmsScreenResync(pDisplay); // Was max7456RefreshAll(); wedges during heavy SPI?
}
#endif // USE_FLASHFS
uint8_t featureBlackbox = 0;
OSD_UINT8_t entryBlackboxRateDenom = {&masterConfig.blackbox_rate_denom,1,32,1};
OSD_Entry menuBlackbox[] =
{
{"--- BLACKBOX ---", OME_Label, NULL, NULL, 0},
{"ENABLED", OME_Bool, NULL, &featureBlackbox, 0},
{"RATE DENOM", OME_UINT8, NULL, &entryBlackboxRateDenom, 0},
#ifdef USE_FLASHFS
{"ERASE FLASH", OME_Submenu, cmsx_EraseFlash, NULL, 0},
#endif // USE_FLASHFS
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
//
// VTX
//
#if defined(VTX) || defined(USE_RTC6705)
uint8_t featureVtx = 0, vtxBand, vtxChannel;
static const char * const vtxBandNames[] = {
"BOSCAM A",
"BOSCAM B",
"BOSCAM E",
"FATSHARK",
"RACEBAND",
};
OSD_TAB_t entryVtxBand = {&vtxBand,4,&vtxBandNames[0]};
OSD_UINT8_t entryVtxChannel = {&vtxChannel, 1, 8, 1};
#ifdef VTX
OSD_UINT8_t entryVtxMode = {&masterConfig.vtx_mode, 0, 2, 1};
OSD_UINT16_t entryVtxMhz = {&masterConfig.vtx_mhz, 5600, 5950, 1};
#endif // VTX
OSD_Entry menu_vtx[] =
{
{"--- VTX ---", OME_Label, NULL, NULL, 0},
{"ENABLED", OME_Bool, NULL, &featureVtx, 0},
#ifdef VTX
{"VTX MODE", OME_UINT8, NULL, &entryVtxMode, 0},
{"VTX MHZ", OME_UINT16, NULL, &entryVtxMhz, 0},
#endif // VTX
{"BAND", OME_TAB, NULL, &entryVtxBand, 0},
{"CHANNEL", OME_UINT8, NULL, &entryVtxChannel, 0},
#ifdef USE_RTC6705
{"LOW POWER", OME_Bool, NULL, &masterConfig.vtx_power, 0},
#endif // USE_RTC6705
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
#endif // VTX || USE_RTC6705
#if 0
#ifdef VTX_SMARTAUDIO
#include "io/vtx_smartaudio.h"
@ -1194,191 +979,40 @@ OSD_Entry menu_vtxSmartAudio[] =
{ NULL, OME_END, NULL, NULL, 0 }
};
#endif // VTX_SMARTAUDIO
#endif // 0
//
// LED_STRIP
//
#ifdef LED_STRIP
//local variable to keep color value
uint8_t ledColor;
static const char * const LED_COLOR_NAMES[] = {
"BLACK ",
"WHITE ",
"RED ",
"ORANGE ",
"YELLOW ",
"LIME GRN",
"GREEN ",
"MINT GRN",
"CYAN ",
"LT BLUE ",
"BLUE ",
"DK VIOLT",
"MAGENTA ",
"DEEP PNK"
};
//find first led with color flag and restore color index
//after saving all leds with flags color will have color set in OSD
static void getLedColor(void)
{
for (int ledIndex = 0; ledIndex < LED_MAX_STRIP_LENGTH; ledIndex++) {
const ledConfig_t *ledConfig = &masterConfig.ledConfigs[ledIndex];
int fn = ledGetFunction(ledConfig);
if (fn == LED_FUNCTION_COLOR) {
ledColor = ledGetColor(ledConfig);
break;
}
}
}
//udate all leds with flag color
static long applyLedColor(displayPort_t *pDisplay, void *ptr)
{
UNUSED(ptr);
UNUSED(pDisplay); // Arrgh
for (int ledIndex = 0; ledIndex < LED_MAX_STRIP_LENGTH; ledIndex++) {
ledConfig_t *ledConfig = &masterConfig.ledConfigs[ledIndex];
if (ledGetFunction(ledConfig) == LED_FUNCTION_COLOR)
*ledConfig = DEFINE_LED(ledGetX(ledConfig), ledGetY(ledConfig), ledColor, ledGetDirection(ledConfig), ledGetFunction(ledConfig), ledGetOverlay(ledConfig), 0);
}
return 0;
}
static uint8_t featureLedstrip;
OSD_TAB_t entryLed = {&ledColor, 13, &LED_COLOR_NAMES[0]};
OSD_Entry menuLedstrip[] =
{
{"--- LED STRIP ---", OME_Label, NULL, NULL, 0},
{"ENABLED", OME_Bool, NULL, &featureLedstrip, 0},
{"LED COLOR", OME_TAB, applyLedColor, &entryLed, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
#endif // LED_STRIP
#ifdef OSD
//
// OSD specific menu pages and items
// XXX Should be part of the osd.c, or new osd_cms.c.
//
OSD_UINT8_t entryAlarmRssi = {&masterConfig.osdProfile.rssi_alarm, 5, 90, 5};
OSD_UINT16_t entryAlarmCapacity = {&masterConfig.osdProfile.cap_alarm, 50, 30000, 50};
OSD_UINT16_t enryAlarmFlyTime = {&masterConfig.osdProfile.time_alarm, 1, 200, 1};
OSD_UINT16_t entryAlarmAltitude = {&masterConfig.osdProfile.alt_alarm, 1, 200, 1};
OSD_Entry menuAlarms[] =
{
{"--- ALARMS ---", OME_Label, NULL, NULL, 0},
{"RSSI", OME_UINT8, NULL, &entryAlarmRssi, 0},
{"MAIN BAT", OME_UINT16, NULL, &entryAlarmCapacity, 0},
{"FLY TIME", OME_UINT16, NULL, &enryAlarmFlyTime, 0},
{"MAX ALT", OME_UINT16, NULL, &entryAlarmAltitude, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
OSD_Entry menuOsdActiveElems[] =
{
{"--- ACTIV ELEM ---", OME_Label, NULL, NULL, 0},
{"RSSI", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE], 0},
{"MAIN BATTERY", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE], 0},
{"HORIZON", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON], 0},
{"HORIZON SIDEBARS", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS], 0},
{"UPTIME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ONTIME], 0},
{"FLY TIME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_FLYTIME], 0},
{"FLY MODE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_FLYMODE], 0},
{"NAME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME], 0},
{"THROTTLE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS], 0},
#ifdef VTX
{"VTX CHAN", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL]},
#endif // VTX
{"CURRENT (A)", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW], 0},
{"USED MAH", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN], 0},
#ifdef GPS
{"GPS SPEED", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_GPS_SPEED], 0},
{"GPS SATS.", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_GPS_SATS], 0},
#endif // GPS
{"ALTITUDE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ALTITUDE], 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
OSD_Entry menuOsdLayout[] =
{
{"---SCREEN LAYOUT---", OME_Label, NULL, NULL, 0},
{"ACTIVE ELEM.", OME_Submenu, cmsMenuChange, &menuOsdActiveElems[0], 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
#endif // OSD
//
// Info
//
static char infoGitRev[GIT_SHORT_REVISION_LENGTH];
static char infoTargetName[] = __TARGET__;
#include "msp/msp_protocol.h" // XXX for FC identification... not available elsewhere
OSD_Entry menuInfo[] = {
{ "--- INFO ---", OME_Label, NULL, NULL, 0 },
{ BETAFLIGHT_IDENTIFIER, OME_Label, NULL, NULL, 0 },
{ FC_VERSION_STRING, OME_Label, NULL, NULL, 0 },
{ infoGitRev, OME_Label, NULL, NULL, 0 },
{ infoTargetName, OME_Label, NULL, NULL, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
void cmsx_InfoInit(void)
{
int i;
for (i = 0 ; i < GIT_SHORT_REVISION_LENGTH ; i++) {
if (shortGitRevision[i] >= 'a' && shortGitRevision[i] <= 'f')
infoGitRev[i] = shortGitRevision[i] - 'a' + 'A';
else
infoGitRev[i] = shortGitRevision[i];
}
}
// Features
OSD_Entry menuFeatures[] =
{
{"--- FEATURES ---", OME_Label, NULL, NULL, 0},
{"BLACKBOX", OME_Submenu, cmsMenuChange, &menuBlackbox[0], 0},
{"BLACKBOX", OME_Submenu, cmsMenuChange, cmsx_menuBlackbox, 0},
#if defined(VTX) || defined(USE_RTC6705)
{"VTX", OME_Submenu, cmsMenuChange, &menu_vtx[0], 0},
{"VTX", OME_Submenu, cmsMenuChange, cmsx_menuVtx, 0},
#endif // VTX || USE_RTC6705
#if defined(VTX_SMARTAUDIO)
{"VTX", OME_Submenu, cmsMenuChange, &menu_vtxSmartAudio[0], 0},
{"VTX", OME_Submenu, cmsMenuChange, cmsx_menuVtxSmartAudio, 0},
#endif
#ifdef LED_STRIP
{"LED STRIP", OME_Submenu, cmsMenuChange, &menuLedstrip[0], 0},
{"LED STRIP", OME_Submenu, cmsMenuChange, cmsx_menuLedstrip, 0},
#endif // LED_STRIP
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
// Main
OSD_Entry menuMain[] =
{
{"--- MAIN MENU ---", OME_Label, NULL, NULL, 0},
{"CFG&IMU", OME_Submenu, cmsMenuChange, &menuImu[0], 0},
{"FEATURES", OME_Submenu, cmsMenuChange, &menuFeatures[0], 0},
{"CFG&IMU", OME_Submenu, cmsMenuChange, cmsx_menuImu, 0},
{"FEATURES", OME_Submenu, cmsMenuChange, menuFeatures, 0},
#ifdef OSD
{"SCR LAYOUT", OME_Submenu, cmsMenuChange, &menuOsdLayout[0], 0},
{"ALARMS", OME_Submenu, cmsMenuChange, &menuAlarms[0], 0},
{"SCR LAYOUT", OME_Submenu, cmsMenuChange, cmsx_menuOsdLayout, 0},
{"ALARMS", OME_Submenu, cmsMenuChange, cmsx_menuAlarms, 0},
#endif
{"INFO", OME_Submenu, cmsMenuChange, &menuInfo[0], 0},
{"FC&FW INFO", OME_Submenu, cmsMenuChange, menuInfo, 0},
{"SAVE&REBOOT", OME_OSD_Exit, cmsMenuExit, (void*)1, 0},
{"EXIT", OME_OSD_Exit, cmsMenuExit, (void*)0, 0},
{NULL,OME_END, NULL, NULL, 0}
@ -1386,60 +1020,33 @@ OSD_Entry menuMain[] =
void cmsx_FeatureRead(void)
{
featureBlackbox = feature(FEATURE_BLACKBOX) ? 1 : 0;
cmsx_Blackbox_FeatureRead();
#ifdef LED_STRIP
featureLedstrip = feature(FEATURE_LED_STRIP) ? 1 : 0;
getLedColor();
cmsx_Ledstrip_FeatureRead();
cmsx_Ledstrip_ConfigRead();
#endif
#if defined(VTX) || defined(USE_RTC6705)
featureVtx = feature(FEATURE_VTX) ? 1 : 0;
cmsx_Vtx_FeatureRead();
cmsx_Vtx_ConfigRead();
#endif // VTX || USE_RTC6705
#ifdef VTX
vtxBand = masterConfig.vtxBand;
vtxChannel = masterConfig.vtx_channel + 1;
#endif // VTX
#ifdef USE_RTC6705
vtxBand = masterConfig.vtx_channel / 8;
vtxChannel = masterConfig.vtx_channel % 8 + 1;
#endif // USE_RTC6705
}
void cmsx_FeatureWriteback(void)
{
if (featureBlackbox)
featureSet(FEATURE_BLACKBOX);
else
featureClear(FEATURE_BLACKBOX);
cmsx_Blackbox_FeatureWriteback();
#ifdef LED_STRIP
if (featureLedstrip)
featureSet(FEATURE_LED_STRIP);
else
featureClear(FEATURE_LED_STRIP);
cmsx_Ledstrip_FeatureWriteback();
#endif
#if defined(VTX) || defined(USE_RTC6705)
if (featureVtx)
featureSet(FEATURE_VTX);
else
featureClear(FEATURE_VTX);
cmsx_Vtx_FeatureWriteback();
cmsx_Vtx_ConfigWriteback();
#endif // VTX || USE_RTC6705
#ifdef VTX
masterConfig.vtxBand = vtxBand;
masterConfig.vtx_channel = vtxChannel - 1;
#endif // VTX
#ifdef USE_RTC6705
masterConfig.vtx_channel = vtxBand * 8 + vtxChannel - 1;
#endif // USE_RTC6705
saveConfigAndNotify();
}
#endif // CMS

View file

@ -1,40 +1,44 @@
#pragma once
typedef struct screenFnVTable_s {
struct displayPort_s;
typedef struct displayPortVTable_s {
int (*begin)(void);
int (*end)(void);
int (*clear)(void);
int (*write)(uint8_t, uint8_t, char *);
int (*write)(uint8_t col, uint8_t row, char *text);
int (*heartbeat)(void);
void (*resync)(void);
} screenFnVTable_t;
void (*resync)(struct displayPort_s *pPort);
uint32_t (*txBytesFree)(void);
} displayPortVTable_t;
typedef struct displayPort_s {
displayPortVTable_t *vTable;
uint8_t rows;
uint8_t cols;
uint16_t buftime;
uint16_t bufsize;
uint16_t batchsize; // Computed by CMS
screenFnVTable_t *VTable;
// CMS state
bool cleared;
} displayPort_t;
// Device management
typedef void (*cmsDeviceInitFuncPtr)(displayPort_t *);
typedef void (*cmsDeviceInitFuncPtr)(displayPort_t *pPort);
bool cmsDeviceRegister(cmsDeviceInitFuncPtr);
// For main.c and scheduler
void cmsInit(void);
void cmsHandler(uint32_t);
void cmsHandler(uint32_t currentTime);
// Required for external CMS tables
void cmsScreenClear(displayPort_t *pPort);
void cmsScreenResync(displayPort_t *pPort);
int cmsScreenWrite(displayPort_t *pPort, uint8_t x, uint8_t y, char *s);
long cmsChangeScreen(displayPort_t *, void *);
long cmsExitMenu(displayPort_t *, void *);
#define STARTUP_HELP_TEXT1 "MENU: THR MID"
#define STARTUP_HELP_TEXT2 "+ YAW LEFT"
#define STARTUP_HELP_TEXT3 "+ PITCH UP"
long cmsMenuChange(displayPort_t *pPort, void *ptr);
long cmsMenuExit(displayPort_t *pPort, void *ptr);
#define CMS_STARTUP_HELP_TEXT1 "MENU: THR MID"
#define CMS_STARTUP_HELP_TEXT2 "+ YAW LEFT"
#define CMS_STARTUP_HELP_TEXT3 "+ PITCH UP"

View file

@ -0,0 +1,77 @@
//
// CMS things for blackbox and flashfs.
// Should be part of blackbox.c (or new blackbox/blackbox_cms.c) and io/flashfs.c
//
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <ctype.h>
#include "platform.h"
#include "build/version.h"
#ifdef CMS
#include "drivers/system.h"
#include "config/config_profile.h"
#include "config/config_master.h"
#include "config/feature.h"
#include "io/cms.h"
#include "io/cms_types.h"
#include "io/cms_blackbox.h"
#include "io/flashfs.h"
#ifdef USE_FLASHFS
long cmsx_EraseFlash(displayPort_t *pDisplay, void *ptr)
{
UNUSED(ptr);
cmsScreenClear(pDisplay);
cmsScreenWrite(pDisplay, 5, 3, "ERASING FLASH...");
cmsScreenResync(pDisplay); // Was max7456RefreshAll(); Why at this timing?
flashfsEraseCompletely();
while (!flashfsIsReady()) {
delay(100);
}
cmsScreenClear(pDisplay);
cmsScreenResync(pDisplay); // Was max7456RefreshAll(); wedges during heavy SPI?
return 0;
}
#endif // USE_FLASHFS
uint8_t cmsx_FeatureBlackbox;
OSD_UINT8_t entryBlackboxRateDenom = {&masterConfig.blackbox_rate_denom,1,32,1};
OSD_Entry cmsx_menuBlackbox[] =
{
{"--- BLACKBOX ---", OME_Label, NULL, NULL, 0},
{"ENABLED", OME_Bool, NULL, &cmsx_FeatureBlackbox, 0},
{"RATE DENOM", OME_UINT8, NULL, &entryBlackboxRateDenom, 0},
#ifdef USE_FLASHFS
{"ERASE FLASH", OME_Submenu, cmsx_EraseFlash, NULL, 0},
#endif // USE_FLASHFS
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
void cmsx_Blackbox_FeatureRead(void)
{
cmsx_FeatureBlackbox = feature(FEATURE_BLACKBOX) ? 1 : 0;
}
void cmsx_Blackbox_FeatureWriteback(void)
{
if (cmsx_FeatureBlackbox)
featureSet(FEATURE_BLACKBOX);
else
featureClear(FEATURE_BLACKBOX);
}
#endif

View file

@ -0,0 +1,4 @@
extern OSD_Entry cmsx_menuBlackbox[];
void cmsx_Blackbox_FeatureRead(void);
void cmsx_Blackbox_FeatureWriteback(void);

206
src/main/io/cms_imu.c Normal file
View file

@ -0,0 +1,206 @@
// Menu contents for PID, RATES, RC preview, misc
// Should be part of the relevant .c file.
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <ctype.h>
#include "platform.h"
#include "build/version.h"
#ifdef CMS
#include "drivers/system.h"
//#include "common/typeconversion.h"
#include "io/cms.h"
#include "io/cms_types.h"
#include "io/cms_imu.h"
#include "fc/config.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "flight/pid.h"
#include "config/config_profile.h"
#include "config/config_master.h"
#include "config/feature.h"
OSD_UINT8_t entryPidProfile = {&masterConfig.current_profile_index, 0, MAX_PROFILE_COUNT, 1};
uint8_t tempPid[4][3];
static OSD_UINT8_t entryRollP = {&tempPid[PIDROLL][0], 10, 150, 1};
static OSD_UINT8_t entryRollI = {&tempPid[PIDROLL][1], 1, 150, 1};
static OSD_UINT8_t entryRollD = {&tempPid[PIDROLL][2], 0, 150, 1};
static OSD_UINT8_t entryPitchP = {&tempPid[PIDPITCH][0], 10, 150, 1};
static OSD_UINT8_t entryPitchI = {&tempPid[PIDPITCH][1], 1, 150, 1};
static OSD_UINT8_t entryPitchD = {&tempPid[PIDPITCH][2], 0, 150, 1};
static OSD_UINT8_t entryYawP = {&tempPid[PIDYAW][0], 10, 150, 1};
static OSD_UINT8_t entryYawI = {&tempPid[PIDYAW][1], 1, 150, 1};
static OSD_UINT8_t entryYawD = {&tempPid[PIDYAW][2], 0, 150, 1};
void cmsx_PidRead(void)
{
uint8_t i;
for (i = 0; i < 3; i++) {
tempPid[i][0] = masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[i];
tempPid[i][1] = masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[i];
tempPid[i][2] = masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[i];
}
tempPid[3][0] = masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDLEVEL];
tempPid[3][1] = masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDLEVEL];
tempPid[3][2] = masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDLEVEL];
}
void cmsx_PidWriteback(void)
{
uint8_t i;
for (i = 0; i < 3; i++) {
masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[i] = tempPid[i][0];
masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[i] = tempPid[i][1];
masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[i] = tempPid[i][2];
}
masterConfig.profile[masterConfig.current_profile_index].pidProfile.P8[PIDLEVEL] = tempPid[3][0];
masterConfig.profile[masterConfig.current_profile_index].pidProfile.I8[PIDLEVEL] = tempPid[3][1];
masterConfig.profile[masterConfig.current_profile_index].pidProfile.D8[PIDLEVEL] = tempPid[3][2];
}
OSD_Entry cmsx_menuPid[] =
{
{"--- PID ---", OME_Label, NULL, NULL, 0},
{"ROLL P", OME_UINT8, NULL, &entryRollP, 0},
{"ROLL I", OME_UINT8, NULL, &entryRollI, 0},
{"ROLL D", OME_UINT8, NULL, &entryRollD, 0},
{"PITCH P", OME_UINT8, NULL, &entryPitchP, 0},
{"PITCH I", OME_UINT8, NULL, &entryPitchI, 0},
{"PITCH D", OME_UINT8, NULL, &entryPitchD, 0},
{"YAW P", OME_UINT8, NULL, &entryYawP, 0},
{"YAW I", OME_UINT8, NULL, &entryYawI, 0},
{"YAW D", OME_UINT8, NULL, &entryYawD, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
//
// Rate & Expo
//
controlRateConfig_t rateProfile;
static OSD_FLOAT_t entryRollRate = {&rateProfile.rates[0], 0, 250, 1, 10};
static OSD_FLOAT_t entryPitchRate = {&rateProfile.rates[1], 0, 250, 1, 10};
static OSD_FLOAT_t entryYawRate = {&rateProfile.rates[2], 0, 250, 1, 10};
static OSD_FLOAT_t entryRcRate = {&rateProfile.rcRate8, 0, 200, 1, 10};
static OSD_FLOAT_t entryRcYawRate = {&rateProfile.rcYawRate8, 0, 200, 1, 10};
static OSD_FLOAT_t entryRcExpo = {&rateProfile.rcExpo8, 0, 100, 1, 10};
static OSD_FLOAT_t entryRcExpoYaw = {&rateProfile.rcYawExpo8, 0, 100, 1, 10};
static OSD_FLOAT_t extryTpaEntry = {&rateProfile.dynThrPID, 0, 70, 1, 10};
static OSD_UINT16_t entryTpaBreak = {&rateProfile.tpa_breakpoint, 1100, 1800, 10};
static OSD_FLOAT_t entryPSetpoint = {&masterConfig.profile[0].pidProfile.setpointRelaxRatio, 0, 100, 1, 10};
static OSD_FLOAT_t entryDSetpoint = {&masterConfig.profile[0].pidProfile.dtermSetpointWeight, 0, 255, 1, 10};
void cmsx_RateExpoRead()
{
memcpy(&rateProfile, &masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile], sizeof(controlRateConfig_t));
}
void cmsx_RateExpoWriteback()
{
memcpy(&masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile], &rateProfile, sizeof(controlRateConfig_t));
}
OSD_Entry cmsx_menuRateExpo[] =
{
{"--- RATE&EXPO ---", OME_Label, NULL, NULL, 0},
{"RC RATE", OME_FLOAT, NULL, &entryRcYawRate, 0},
{"RC YAW RATE", OME_FLOAT, NULL, &entryRcRate, 0},
{"ROLL SUPER", OME_FLOAT, NULL, &entryRollRate, 0},
{"PITCH SUPER", OME_FLOAT, NULL, &entryPitchRate, 0},
{"YAW SUPER", OME_FLOAT, NULL, &entryYawRate, 0},
{"RC EXPO", OME_FLOAT, NULL, &entryRcExpo, 0},
{"RC YAW EXPO", OME_FLOAT, NULL, &entryRcExpoYaw, 0},
{"THR PID ATT", OME_FLOAT, NULL, &extryTpaEntry, 0},
{"TPA BRKPT", OME_UINT16, NULL, &entryTpaBreak, 0},
{"D SETPT", OME_FLOAT, NULL, &entryDSetpoint, 0},
{"D SETPT TRN", OME_FLOAT, NULL, &entryPSetpoint, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
//
// RC preview
//
static OSD_INT16_t entryRcRoll = {&rcData[ROLL], 1, 2500, 0};
static OSD_INT16_t entryRcPitch = {&rcData[PITCH], 1, 2500, 0};
static OSD_INT16_t entryRcThr = {&rcData[THROTTLE], 1, 2500, 0};
static OSD_INT16_t entryRcYaw = {&rcData[YAW], 1, 2500, 0};
static OSD_INT16_t entryRcAux1 = {&rcData[AUX1], 1, 2500, 0};
static OSD_INT16_t entryRcAux2 = {&rcData[AUX2], 1, 2500, 0};
static OSD_INT16_t entryRcAux3 = {&rcData[AUX3], 1, 2500, 0};
static OSD_INT16_t entryRcAux4 = {&rcData[AUX4], 1, 2500, 0};
OSD_Entry cmsx_menuRc[] =
{
{"--- RC PREV ---", OME_Label, NULL, NULL, 0},
{"ROLL", OME_Poll_INT16, NULL, &entryRcRoll, 0},
{"PITCH", OME_Poll_INT16, NULL, &entryRcPitch, 0},
{"THR", OME_Poll_INT16, NULL, &entryRcThr, 0},
{"YAW", OME_Poll_INT16, NULL, &entryRcYaw, 0},
{"AUX1", OME_Poll_INT16, NULL, &entryRcAux1, 0},
{"AUX2", OME_Poll_INT16, NULL, &entryRcAux2, 0},
{"AUX3", OME_Poll_INT16, NULL, &entryRcAux3, 0},
{"AUX4", OME_Poll_INT16, NULL, &entryRcAux4, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
//
// Misc
//
OSD_UINT16_t entryMinThrottle = {&masterConfig.motorConfig.minthrottle, 1020, 1300, 10};
OSD_UINT8_t entryGyroSoftLpfHz = {&masterConfig.gyro_soft_lpf_hz, 0, 255, 1};
OSD_UINT16_t entryDtermLpf = {&masterConfig.profile[0].pidProfile.dterm_lpf_hz, 0, 500, 5};
OSD_UINT16_t entryYawLpf = {&masterConfig.profile[0].pidProfile.yaw_lpf_hz, 0, 500, 5};
OSD_UINT16_t entryYawPLimit = {&masterConfig.profile[0].pidProfile.yaw_p_limit, 100, 500, 5};
OSD_UINT8_t entryVbatScale = {&masterConfig.batteryConfig.vbatscale, 1, 250, 1};
OSD_UINT8_t entryVbatMaxCell = {&masterConfig.batteryConfig.vbatmaxcellvoltage, 10, 50, 1};
OSD_Entry menuImuMisc[]=
{
{"--- MISC ---", OME_Label, NULL, NULL, 0},
{"GYRO LPF", OME_UINT8, NULL, &entryGyroSoftLpfHz, 0},
{"DTERM LPF", OME_UINT16, NULL, &entryDtermLpf, 0},
{"YAW LPF", OME_UINT16, NULL, &entryYawLpf, 0},
{"YAW P LIM", OME_UINT16, NULL, &entryYawPLimit, 0},
{"MIN THR", OME_UINT16, NULL, &entryMinThrottle, 0},
{"VBAT SCALE", OME_UINT8, NULL, &entryVbatScale, 0},
{"VBAT CLMAX", OME_UINT8, NULL, &entryVbatMaxCell, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
OSD_Entry cmsx_menuImu[] =
{
{"--- CFG.IMU ---", OME_Label, NULL, NULL, 0},
{"PID PROF", OME_UINT8, NULL, &entryPidProfile, 0},
{"PID", OME_Submenu, cmsMenuChange, cmsx_menuPid, 0},
{"RATE&RXPO", OME_Submenu, cmsMenuChange, cmsx_menuRateExpo, 0},
{"RC PREV", OME_Submenu, cmsMenuChange, cmsx_menuRc, 0},
{"MISC", OME_Submenu, cmsMenuChange, menuImuMisc, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
#endif // CMS

13
src/main/io/cms_imu.h Normal file
View file

@ -0,0 +1,13 @@
extern OSD_Entry cmsx_menuImu[];
// All of below should be gone.
extern OSD_Entry cmsx_menuPid[];
extern OSD_Entry cmsx_menuRc[];
extern OSD_Entry cmsx_menuRateExpo[];
void cmsx_PidRead(void);
void cmsx_PidWriteback(void);
void cmsx_RateExpoRead(void);
void cmsx_RateExpoWriteback(void);

107
src/main/io/cms_ledstrip.c Normal file
View file

@ -0,0 +1,107 @@
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
#include <ctype.h>
#include "platform.h"
#include "build/version.h"
#ifdef CMS
#include "drivers/system.h"
#include "config/config_profile.h"
#include "config/config_master.h"
#include "config/feature.h"
#include "io/cms.h"
#include "io/cms_types.h"
#include "io/cms_blackbox.h"
#ifdef LED_STRIP
//local variable to keep color value
uint8_t ledColor;
static const char * const LED_COLOR_NAMES[] = {
"BLACK ",
"WHITE ",
"RED ",
"ORANGE ",
"YELLOW ",
"LIME GRN",
"GREEN ",
"MINT GRN",
"CYAN ",
"LT BLUE ",
"BLUE ",
"DK VIOLT",
"MAGENTA ",
"DEEP PNK"
};
//find first led with color flag and restore color index
//after saving all leds with flags color will have color set in OSD
void cmsx_GetLedColor(void)
{
for (int ledIndex = 0; ledIndex < LED_MAX_STRIP_LENGTH; ledIndex++) {
const ledConfig_t *ledConfig = &masterConfig.ledConfigs[ledIndex];
int fn = ledGetFunction(ledConfig);
if (fn == LED_FUNCTION_COLOR) {
ledColor = ledGetColor(ledConfig);
break;
}
}
}
//udate all leds with flag color
static long applyLedColor(displayPort_t *pDisplay, void *ptr)
{
UNUSED(ptr);
UNUSED(pDisplay); // Arrgh
for (int ledIndex = 0; ledIndex < LED_MAX_STRIP_LENGTH; ledIndex++) {
ledConfig_t *ledConfig = &masterConfig.ledConfigs[ledIndex];
if (ledGetFunction(ledConfig) == LED_FUNCTION_COLOR)
*ledConfig = DEFINE_LED(ledGetX(ledConfig), ledGetY(ledConfig), ledColor, ledGetDirection(ledConfig), ledGetFunction(ledConfig), ledGetOverlay(ledConfig), 0);
}
return 0;
}
uint8_t cmsx_FeatureLedstrip;
OSD_TAB_t entryLed = {&ledColor, 13, &LED_COLOR_NAMES[0]};
OSD_Entry cmsx_menuLedstrip[] =
{
{"--- LED STRIP ---", OME_Label, NULL, NULL, 0},
{"ENABLED", OME_Bool, NULL, &cmsx_FeatureLedstrip, 0},
{"LED COLOR", OME_TAB, applyLedColor, &entryLed, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
void cmsx_Ledstrip_FeatureRead(void)
{
cmsx_FeatureLedstrip = feature(FEATURE_LED_STRIP) ? 1 : 0;
}
void cmsx_Ledstrip_FeatureWriteback(void)
{
if (cmsx_FeatureLedstrip)
featureSet(FEATURE_LED_STRIP);
else
featureClear(FEATURE_LED_STRIP);
}
void cmsx_Ledstrip_ConfigRead(void)
{
cmsx_GetLedColor();
}
#endif // LED_STRIP
#endif // CMS

View file

@ -0,0 +1,6 @@
extern OSD_Entry cmsx_menuLedstrip[];
void cmsx_Ledstrip_FeatureRead(void);
void cmsx_Ledstrip_FeatureWriteback(void);
void cmsx_Ledstrip_ConfigRead(void);

2
src/main/io/cms_osd.h Normal file
View file

@ -0,0 +1,2 @@
extern OSD_Entry cmsx_menuAlarms[];
extern OSD_Entry cmsx_menuOsdLayout[];

View file

@ -8,6 +8,7 @@
typedef long (*OSDMenuFuncPtr)(displayPort_t *, void *);
//type of elements
typedef enum
{
OME_Label,
@ -20,9 +21,12 @@ typedef enum
OME_UINT16,
OME_INT16,
OME_Poll_INT16,
OME_String,
OME_FLOAT, //only up to 255 value and cant be 2.55 or 25.5, just for PID's
//wlasciwosci elementow
#ifdef OSD
OME_VISIBLE,
#endif
OME_TAB,
OME_END,
} OSD_MenuElement;
@ -95,3 +99,8 @@ typedef struct
uint8_t max;
const char * const *names;
} OSD_TAB_t;
typedef struct
{
char *val;
} OSD_String_t;

96
src/main/io/cms_vtx.c Normal file
View file

@ -0,0 +1,96 @@
#include <stdbool.h>
#include <stdint.h>
#include <ctype.h>
#include "platform.h"
#include "build/version.h"
#include "io/cms.h"
#include "io/cms_types.h"
#include "io/cms_vtx.h"
#include "config/config_profile.h"
#include "config/config_master.h"
#include "config/feature.h"
#ifdef CMS
#if defined(VTX) || defined(USE_RTC6705)
uint8_t cmsx_featureVtx = 0, cmsx_vtxBand, cmsx_vtxChannel;
static const char * const vtxBandNames[] = {
"BOSCAM A",
"BOSCAM B",
"BOSCAM E",
"FATSHARK",
"RACEBAND",
};
OSD_TAB_t entryVtxBand = {&cmsx_vtxBand,4,&vtxBandNames[0]};
OSD_UINT8_t entryVtxChannel = {&cmsx_vtxChannel, 1, 8, 1};
#ifdef VTX
OSD_UINT8_t entryVtxMode = {&masterConfig.vtx_mode, 0, 2, 1};
OSD_UINT16_t entryVtxMhz = {&masterConfig.vtx_mhz, 5600, 5950, 1};
#endif // VTX
OSD_Entry cmsx_menuVtx[] =
{
{"--- VTX ---", OME_Label, NULL, NULL, 0},
{"ENABLED", OME_Bool, NULL, &cmsx_featureVtx, 0},
#ifdef VTX
{"VTX MODE", OME_UINT8, NULL, &entryVtxMode, 0},
{"VTX MHZ", OME_UINT16, NULL, &entryVtxMhz, 0},
#endif // VTX
{"BAND", OME_TAB, NULL, &entryVtxBand, 0},
{"CHANNEL", OME_UINT8, NULL, &entryVtxChannel, 0},
#ifdef USE_RTC6705
{"LOW POWER", OME_Bool, NULL, &masterConfig.vtx_power, 0},
#endif // USE_RTC6705
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
void cmsx_Vtx_FeatureRead(void)
{
cmsx_featureVtx = feature(FEATURE_VTX) ? 1 : 0;
}
void cmsx_Vtx_FeatureWriteback(void)
{
if (cmsx_featureVtx)
featureSet(FEATURE_VTX);
else
featureClear(FEATURE_VTX);
}
void cmsx_Vtx_ConfigRead(void)
{
#ifdef VTX
cmsx_vtxBand = masterConfig.vtxBand;
cmsx_vtxChannel = masterConfig.vtx_channel + 1;
#endif // VTX
#ifdef USE_RTC6705
cmsx_vtxBand = masterConfig.vtx_channel / 8;
cmsx_vtxChannel = masterConfig.vtx_channel % 8 + 1;
#endif // USE_RTC6705
}
void cmsx_Vtx_ConfigWriteback(void)
{
#ifdef VTX
masterConfig.vtxBand = cmsx_vtxBand;
masterConfig.vtx_channel = cmsx_vtxChannel - 1;
#endif // VTX
#ifdef USE_RTC6705
masterConfig.vtx_channel = cmsx_vtxBand * 8 + cmsx_vtxChannel - 1;
#endif // USE_RTC6705
}
#endif // VTX || USE_RTC6705
#endif // CMS

7
src/main/io/cms_vtx.h Normal file
View file

@ -0,0 +1,7 @@
extern OSD_Entry cmsx_menuVtx[];
void cmsx_Vtx_FeatureRead(void);
void cmsx_Vtx_FeatureWriteback(void);
void cmsx_Vtx_ConfigRead(void);
void cmsx_Vtx_ConfigWriteback(void);

View file

@ -21,7 +21,9 @@
#include "platform.h"
#ifdef DISPLAY
#ifdef USE_DASHBOARD
#include "common/utils.h"
#include "build/version.h"
#include "build/debug.h"
@ -50,7 +52,10 @@
#include "flight/imu.h"
#include "flight/failsafe.h"
#ifdef OLEDCMS
#include "io/cms.h"
void dashboardCmsInit(displayPort_t *pPort); // Forward
#endif
#ifdef GPS
#include "io/gps.h"
@ -60,7 +65,7 @@
#include "config/feature.h"
#include "config/config_profile.h"
#include "io/display.h"
#include "io/dashboard.h"
#include "rx/rx.h"
@ -76,7 +81,7 @@ controlRateConfig_t *getControlRateConfig(uint8_t profileIndex);
#define PAGE_CYCLE_FREQUENCY (MICROSECONDS_IN_A_SECOND * 5)
static uint32_t nextDisplayUpdateAt = 0;
static bool displayPresent = false;
static bool dashboardPresent = false;
static rxConfig_t *rxConfig;
@ -100,7 +105,7 @@ static const char* const pageTitles[] = {
#ifdef GPS
,"GPS"
#endif
#ifdef ENABLE_DEBUG_OLED_PAGE
#ifdef ENABLE_DEBUG_DASHBOARD_PAGE
,"DEBUG"
#endif
};
@ -118,7 +123,7 @@ const pageId_e cyclePageIds[] = {
#ifndef SKIP_TASK_STATISTICS
,PAGE_TASKS
#endif
#ifdef ENABLE_DEBUG_OLED_PAGE
#ifdef ENABLE_DEBUG_DASHBOARD_PAGE
,PAGE_DEBUG,
#endif
};
@ -146,7 +151,7 @@ typedef struct pageState_s {
static pageState_t pageState;
void resetDisplay(void) {
displayPresent = ug2864hsweg01InitI2C();
dashboardPresent = ug2864hsweg01InitI2C();
}
void LCDprint(uint8_t i) {
@ -564,7 +569,7 @@ void showTasksPage(void)
}
#endif
#ifdef ENABLE_DEBUG_OLED_PAGE
#ifdef ENABLE_DEBUG_DASHBOARD_PAGE
void showDebugPage(void)
{
@ -580,15 +585,15 @@ void showDebugPage(void)
#endif
#ifdef OLEDCMS
static bool displayInCMS = false;
static bool dashboardInCMS = false;
#endif
void displayUpdate(uint32_t currentTime)
void dashboardUpdate(uint32_t currentTime)
{
static uint8_t previousArmedState = 0;
#ifdef OLEDCMS
if (displayInCMS)
if (dashboardInCMS)
return;
#endif
@ -634,13 +639,13 @@ void displayUpdate(uint32_t currentTime)
// user to power off/on the display or connect it while powered.
resetDisplay();
if (!displayPresent) {
if (!dashboardPresent) {
return;
}
handlePageChange();
}
if (!displayPresent) {
if (!dashboardPresent) {
return;
}
@ -677,7 +682,7 @@ void displayUpdate(uint32_t currentTime)
}
break;
#endif
#ifdef ENABLE_DEBUG_OLED_PAGE
#ifdef ENABLE_DEBUG_DASHBOARD_PAGE
case PAGE_DEBUG:
showDebugPage();
break;
@ -691,84 +696,82 @@ void displayUpdate(uint32_t currentTime)
}
void displaySetPage(pageId_e pageId)
void dashboardSetPage(pageId_e pageId)
{
pageState.pageId = pageId;
pageState.pageFlags |= PAGE_STATE_FLAG_FORCE_PAGE_CHANGE;
}
void displayInit(rxConfig_t *rxConfigToUse)
void dashboardInit(rxConfig_t *rxConfigToUse)
{
delay(200);
resetDisplay();
delay(200);
#if defined(CMS) && defined(OLEDCMS)
cmsDeviceRegister(displayCmsInit);
#ifdef OLEDCMS
cmsDeviceRegister(dashboardCmsInit);
#endif
rxConfig = rxConfigToUse;
memset(&pageState, 0, sizeof(pageState));
displaySetPage(PAGE_WELCOME);
dashboardSetPage(PAGE_WELCOME);
displayUpdate(micros());
dashboardUpdate(micros());
displaySetNextPageChangeAt(micros() + (1000 * 1000 * 5));
dashboardSetNextPageChangeAt(micros() + (1000 * 1000 * 5));
}
void displayShowFixedPage(pageId_e pageId)
void dashboardShowFixedPage(pageId_e pageId)
{
displaySetPage(pageId);
displayDisablePageCycling();
dashboardSetPage(pageId);
dashboardDisablePageCycling();
}
void displaySetNextPageChangeAt(uint32_t futureMicros)
void dashboardSetNextPageChangeAt(uint32_t futureMicros)
{
pageState.nextPageAt = futureMicros;
}
void displayEnablePageCycling(void)
void dashboardEnablePageCycling(void)
{
pageState.pageFlags |= PAGE_STATE_FLAG_CYCLE_ENABLED;
}
void displayResetPageCycling(void)
void dashboardResetPageCycling(void)
{
pageState.cycleIndex = CYCLE_PAGE_ID_COUNT - 1; // start at first page
}
void displayDisablePageCycling(void)
void dashboardDisablePageCycling(void)
{
pageState.pageFlags &= ~PAGE_STATE_FLAG_CYCLE_ENABLED;
}
#ifdef OLEDCMS
#include "io/cms.h"
int displayCmsBegin(void)
int dashboardCmsBegin(void)
{
displayInCMS = true;
dashboardInCMS = true;
return 0;
}
int displayCmsEnd(void)
int dashboardCmsEnd(void)
{
displayInCMS = false;
dashboardInCMS = false;
return 0;
}
int displayCmsClear(void)
int dashboardCmsClear(void)
{
i2c_OLED_clear_display_quick();
return 0;
}
int displayCmsWrite(uint8_t x, uint8_t y, char *s)
int dashboardCmsWrite(uint8_t x, uint8_t y, char *s)
{
i2c_OLED_set_xy(x, y);
i2c_OLED_send_string(s);
@ -776,22 +779,36 @@ int displayCmsWrite(uint8_t x, uint8_t y, char *s)
return 0;
}
screenFnVTable_t displayCmsVTable = {
displayCmsBegin,
displayCmsEnd,
displayCmsClear,
displayCmsWrite,
NULL,
NULL,
int dashboardCmsHeartbeat(void)
{
return 0;
}
void dashboardCmsResync(displayPort_t *pPort)
{
UNUSED(pPort);
}
uint32_t dashboardCmsTxBytesFree(void)
{
return UINT32_MAX;
}
displayPortVTable_t dashboardCmsVTable = {
dashboardCmsBegin,
dashboardCmsEnd,
dashboardCmsClear,
dashboardCmsWrite,
dashboardCmsHeartbeat,
dashboardCmsResync,
dashboardCmsTxBytesFree,
};
void displayCmsInit(displayPort_t *pPort)
void dashboardCmsInit(displayPort_t *pPort)
{
pPort->rows = 8;
pPort->cols = 21;
pPort->buftime = 1;
pPort->bufsize = 50000;
pPort->VTable = &displayCmsVTable;
pPort->rows = SCREEN_CHARACTER_ROW_COUNT;
pPort->cols = SCREEN_CHARACTER_COLUMN_COUNT;
pPort->vTable = &dashboardCmsVTable;
}
#endif // OLEDCMS

View file

@ -15,7 +15,7 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#define ENABLE_DEBUG_OLED_PAGE
#define ENABLE_DEBUG_DASHBOARD_PAGE
typedef enum {
PAGE_WELCOME,
@ -30,22 +30,26 @@ typedef enum {
#ifdef GPS
PAGE_GPS,
#endif
#ifdef ENABLE_DEBUG_OLED_PAGE
#ifdef ENABLE_DEBUG_DASHBOARD_PAGE
PAGE_DEBUG,
#endif
} pageId_e;
struct rxConfig_s;
void displayInit(struct rxConfig_s *intialRxConfig);
void displayUpdate(uint32_t currentTime);
void dashboardInit(struct rxConfig_s *intialRxConfig);
void dashboardUpdate(uint32_t currentTime);
void displayShowFixedPage(pageId_e pageId);
void dashboardShowFixedPage(pageId_e pageId);
void dashboardEnablePageCycling(void);
void dashboardDisablePageCycling(void);
void dashboardResetPageCycling(void);
void dashboardSetNextPageChangeAt(uint32_t futureMicros);
void displayEnablePageCycling(void);
void displayDisablePageCycling(void);
void displayResetPageCycling(void);
void displaySetNextPageChangeAt(uint32_t futureMicros);
#ifdef CMS
void displayCmsInit(displayPort_t *);
//void dashboardCmsInit(displayPort_t *pPort);
#endif

View file

@ -41,7 +41,7 @@
#include "io/cms.h"
#include "io/serial.h"
#include "io/display.h"
#include "io/dashboard.h"
#include "io/gps.h"
#include "flight/gps_conversion.h"
@ -1074,9 +1074,9 @@ static bool gpsNewFrameUBLOX(uint8_t data)
static void gpsHandlePassthrough(uint8_t data)
{
gpsNewData(data);
#ifdef DISPLAY
if (feature(FEATURE_DISPLAY)) {
displayUpdate(micros());
#ifdef USE_DASHBOARD
if (feature(FEATURE_DASHBOARD)) {
dashboardUpdate(micros());
}
#endif
@ -1090,9 +1090,9 @@ void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort)
if(!(gpsPort->mode & MODE_TX))
serialSetMode(gpsPort, gpsPort->mode | MODE_TX);
#ifdef DISPLAY
if (feature(FEATURE_DISPLAY)) {
displayShowFixedPage(PAGE_GPS);
#ifdef USE_DASHBOARD
if (feature(FEATURE_DASHBOARD)) {
dashboardShowFixedPage(PAGE_GPS);
}
#endif

View file

@ -266,30 +266,26 @@ void osdDrawSingleElement(uint8_t item)
#endif // VTX
case OSD_CROSSHAIRS:
{
uint8_t *screenBuffer = max7456GetScreenBuffer();
uint16_t position = 194;
elemPosX = 14 - 1; // Offset for 1 char to the left
elemPosY = 6;
if (maxScreenSize == VIDEO_BUFFER_CHARS_PAL)
position += 30;
screenBuffer[position - 1] = (SYM_AH_CENTER_LINE);
screenBuffer[position + 1] = (SYM_AH_CENTER_LINE_RIGHT);
screenBuffer[position] = (SYM_AH_CENTER);
return;
}
++elemPosY;
buff[0] = SYM_AH_CENTER_LINE;
buff[1] = SYM_AH_CENTER;
buff[2] = SYM_AH_CENTER_LINE_RIGHT;
buff[3] = 0;
break;
case OSD_ARTIFICIAL_HORIZON:
{
uint8_t *screenBuffer = max7456GetScreenBuffer();
uint16_t position = 194;
elemPosX = 14;
elemPosY = 6 - 4; // Top center of the AH area
int rollAngle = attitude.values.roll;
int pitchAngle = attitude.values.pitch;
if (maxScreenSize == VIDEO_BUFFER_CHARS_PAL)
position += 30;
++elemPosY;
if (pitchAngle > AH_MAX_PITCH)
pitchAngle = AH_MAX_PITCH;
@ -300,13 +296,15 @@ void osdDrawSingleElement(uint8_t item)
if (rollAngle < -AH_MAX_ROLL)
rollAngle = -AH_MAX_ROLL;
for (uint8_t x = 0; x <= 8; x++) {
int y = (rollAngle * (4 - x)) / 64;
y -= pitchAngle / 8;
y += 41;
// Convert pitchAngle to y compensation value
pitchAngle = (pitchAngle / 8) - 41; // 41 = 4 * 9 + 5
for (int8_t x = -4; x <= 4; x++) {
int y = (rollAngle * x) / 64;
y -= pitchAngle;
// y += 41; // == 4 * 9 + 5
if (y >= 0 && y <= 81) {
uint16_t pos = position - 7 + LINE * (y / 9) + 3 - 4 * LINE + x;
screenBuffer[pos] = (SYM_AH_BAR9_0 + (y % 9));
max7456WriteChar(elemPosX + x, elemPosY + (y / 9), (SYM_AH_BAR9_0 + (y % 9)));
}
}
@ -317,23 +315,23 @@ void osdDrawSingleElement(uint8_t item)
case OSD_HORIZON_SIDEBARS:
{
uint8_t *screenBuffer = max7456GetScreenBuffer();
uint16_t position = 194;
elemPosX = 14;
elemPosY = 6;
if (maxScreenSize == VIDEO_BUFFER_CHARS_PAL)
position += 30;
++elemPosY;
// Draw AH sides
int8_t hudwidth = AH_SIDEBAR_WIDTH_POS;
int8_t hudheight = AH_SIDEBAR_HEIGHT_POS;
for (int8_t x = -hudheight; x <= hudheight; x++) {
screenBuffer[position - hudwidth + (x * LINE)] = (SYM_AH_DECORATION);
screenBuffer[position + hudwidth + (x * LINE)] = (SYM_AH_DECORATION);
for (int8_t y = -hudheight; y <= hudheight; y++) {
max7456WriteChar(elemPosX - hudwidth, elemPosY + y, SYM_AH_DECORATION);
max7456WriteChar(elemPosX + hudwidth, elemPosY + y, SYM_AH_DECORATION);
}
// AH level indicators
screenBuffer[position - hudwidth + 1] = (SYM_AH_LEFT);
screenBuffer[position + hudwidth - 1] = (SYM_AH_RIGHT);
max7456WriteChar(elemPosX - hudwidth + 1, elemPosY, SYM_AH_LEFT);
max7456WriteChar(elemPosX + hudwidth - 1, elemPosY, SYM_AH_RIGHT);
return;
}
@ -392,9 +390,11 @@ void osdInit(void)
sprintf(string_buffer, "BF VERSION: %s", FC_VERSION_STRING);
max7456Write(5, 6, string_buffer);
max7456Write(7, 7, STARTUP_HELP_TEXT1);
max7456Write(11, 8, STARTUP_HELP_TEXT2);
max7456Write(11, 9, STARTUP_HELP_TEXT3);
#ifdef CMS
max7456Write(7, 7, CMS_STARTUP_HELP_TEXT1);
max7456Write(11, 8, CMS_STARTUP_HELP_TEXT2);
max7456Write(11, 9, CMS_STARTUP_HELP_TEXT3);
#endif
max7456RefreshAll();
@ -636,6 +636,7 @@ void osdUpdate(uint32_t currentTime)
//
// OSD specific CMS functions
//
#include "io/cms_osd.h"
uint8_t shiftdown;
@ -669,6 +670,23 @@ int osdWrite(uint8_t x, uint8_t y, char *s)
return 0;
}
void osdResync(displayPort_t *pPort)
{
max7456RefreshAll();
pPort->rows = max7456GetRowsCount() - masterConfig.osdProfile.row_shiftdown;
pPort->cols = 30;
}
int osdHeartbeat(void)
{
return 0;
}
uint32_t osdTxBytesFree(void)
{
return UINT32_MAX;
}
#ifdef EDIT_ELEMENT_SUPPORT
void osdEditElement(void *ptr)
{
@ -695,22 +713,70 @@ void osdDrawElementPositioningHelp(void)
}
#endif
screenFnVTable_t osdVTable = {
displayPortVTable_t osdVTable = {
osdMenuBegin,
osdMenuEnd,
osdClearScreen,
osdWrite,
NULL,
max7456RefreshAll,
osdHeartbeat,
osdResync,
osdTxBytesFree,
};
void osdCmsInit(displayPort_t *pPort)
{
shiftdown = masterConfig.osdProfile.row_shiftdown;
pPort->rows = max7456GetRowsCount() - shiftdown;
pPort->cols = 30;
pPort->buftime = 1; // Very fast
pPort->bufsize = 50000; // Very large
pPort->VTable = &osdVTable;
osdResync(pPort);
pPort->vTable = &osdVTable;
}
OSD_UINT8_t entryAlarmRssi = {&masterConfig.osdProfile.rssi_alarm, 5, 90, 5};
OSD_UINT16_t entryAlarmCapacity = {&masterConfig.osdProfile.cap_alarm, 50, 30000, 50};
OSD_UINT16_t enryAlarmFlyTime = {&masterConfig.osdProfile.time_alarm, 1, 200, 1};
OSD_UINT16_t entryAlarmAltitude = {&masterConfig.osdProfile.alt_alarm, 1, 200, 1};
OSD_Entry cmsx_menuAlarms[] =
{
{"--- ALARMS ---", OME_Label, NULL, NULL, 0},
{"RSSI", OME_UINT8, NULL, &entryAlarmRssi, 0},
{"MAIN BAT", OME_UINT16, NULL, &entryAlarmCapacity, 0},
{"FLY TIME", OME_UINT16, NULL, &enryAlarmFlyTime, 0},
{"MAX ALT", OME_UINT16, NULL, &entryAlarmAltitude, 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
OSD_Entry menuOsdActiveElems[] =
{
{"--- ACTIV ELEM ---", OME_Label, NULL, NULL, 0},
{"RSSI", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE], 0},
{"MAIN BATTERY", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE], 0},
{"HORIZON", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON], 0},
{"HORIZON SIDEBARS", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS], 0},
{"UPTIME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ONTIME], 0},
{"FLY TIME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_FLYTIME], 0},
{"FLY MODE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_FLYMODE], 0},
{"NAME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME], 0},
{"THROTTLE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS], 0},
#ifdef VTX
{"VTX CHAN", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL]},
#endif // VTX
{"CURRENT (A)", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW], 0},
{"USED MAH", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN], 0},
#ifdef GPS
{"GPS SPEED", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_GPS_SPEED], 0},
{"GPS SATS.", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_GPS_SATS], 0},
#endif // GPS
{"ALTITUDE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ALTITUDE], 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
OSD_Entry cmsx_menuOsdLayout[] =
{
{"---SCREEN LAYOUT---", OME_Label, NULL, NULL, 0},
{"ACTIVE ELEM.", OME_Submenu, cmsMenuChange, &menuOsdActiveElems[0], 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};
#endif // OSD

View file

@ -148,7 +148,8 @@ static void cliTasks(char *cmdline);
#endif
static void cliVersion(char *cmdline);
static void cliRxRange(char *cmdline);
#if (FLASH_SIZE > 64) && !defined(CLI_MINIMAL_VERBOSITY)
#if (FLASH_SIZE > 64)
static void printResource(uint8_t dumpMask, master_t *defaultConfig);
static void cliResource(char *cmdline);
#endif
#ifdef GPS
@ -203,6 +204,7 @@ typedef enum {
DUMP_ALL = (1 << 3),
DO_DIFF = (1 << 4),
SHOW_DEFAULTS = (1 << 5),
HIDE_UNUSED = (1 << 6),
} dumpFlags_e;
static const char* const emptyName = "-";
@ -237,7 +239,7 @@ static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT
{ RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET }
};
#if (FLASH_SIZE > 64) && !defined(CLI_MINIMAL_VERBOSITY)
#if (FLASH_SIZE > 64)
// sync this with sensors_e
static const char * const sensorTypeNames[] = {
"GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
@ -331,7 +333,7 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("profile", "change profile",
"[<index>]", cliProfile),
CLI_COMMAND_DEF("rateprofile", "change rate profile", "[<index>]", cliRateProfile),
#if (FLASH_SIZE > 64) && !defined(CLI_MINIMAL_VERBOSITY)
#if (FLASH_SIZE > 64)
CLI_COMMAND_DEF("resource", "view currently used resources", NULL, cliResource),
#endif
CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
@ -2744,6 +2746,11 @@ static void printConfig(char *cmdline, bool doDiff)
#endif
printName(dumpMask);
#ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# resources\r\n");
#endif
printResource(dumpMask, &defaultConfig);
#ifndef USE_QUAD_MIXER_ONLY
#ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\n# mixer\r\n");
@ -3726,7 +3733,7 @@ void cliProcess(void)
}
}
#if (FLASH_SIZE > 64) && !defined(CLI_MINIMAL_VERBOSITY)
#if (FLASH_SIZE > 64)
typedef struct {
const uint8_t owner;
@ -3752,13 +3759,72 @@ const cliResourceValue_t resourceTable[] = {
#endif
};
static void printResource(uint8_t dumpMask, master_t *defaultConfig)
{
for (unsigned int i = 0; i < ARRAYLEN(resourceTable); i++) {
const char* owner;
owner = ownerNames[resourceTable[i].owner];
if (resourceTable[i].maxIndex > 0) {
for (int index = 0; index < resourceTable[i].maxIndex; index++) {
ioTag_t ioPtr = *(resourceTable[i].ptr + index);
ioTag_t ioPtrDefault = *(resourceTable[i].ptr + index - (uint32_t)&masterConfig + (uint32_t)defaultConfig);
IO_t io = IOGetByTag(ioPtr);
IO_t ioDefault = IOGetByTag(ioPtrDefault);
bool equalsDefault = io == ioDefault;
const char *format = "resource %s %d %c%02d\r\n";
const char *formatUnassigned = "resource %s %d NONE\r\n";
if (DEFIO_TAG_ISEMPTY(ioDefault)) {
cliDefaultPrintf(dumpMask, equalsDefault, formatUnassigned, owner, RESOURCE_INDEX(index));
} else {
cliDefaultPrintf(dumpMask, equalsDefault, format, owner, RESOURCE_INDEX(index), IO_GPIOPortIdx(ioDefault) + 'A', IO_GPIOPinIdx(ioDefault));
}
if (DEFIO_TAG_ISEMPTY(io)) {
if (!(dumpMask & HIDE_UNUSED)) {
cliDumpPrintf(dumpMask, equalsDefault, formatUnassigned, owner, RESOURCE_INDEX(index));
}
} else {
cliDumpPrintf(dumpMask, equalsDefault, format, owner, RESOURCE_INDEX(index), IO_GPIOPortIdx(io) + 'A', IO_GPIOPinIdx(io));
}
}
} else {
ioTag_t ioPtr = *resourceTable[i].ptr;
ioTag_t ioPtrDefault = *(resourceTable[i].ptr - (uint32_t)&masterConfig + (uint32_t)defaultConfig);
IO_t io = IOGetByTag(ioPtr);
IO_t ioDefault = IOGetByTag(ioPtrDefault);
bool equalsDefault = io == ioDefault;
const char *format = "resource %s %c%02d\r\n";
const char *formatUnassigned = "resource %s NONE\r\n";
if (DEFIO_TAG_ISEMPTY(ioDefault)) {
cliDefaultPrintf(dumpMask, equalsDefault, formatUnassigned, owner);
} else {
cliDefaultPrintf(dumpMask, equalsDefault, format, owner, IO_GPIOPortIdx(ioDefault) + 'A', IO_GPIOPinIdx(ioDefault));
}
if (DEFIO_TAG_ISEMPTY(io)) {
if (!(dumpMask & HIDE_UNUSED)) {
cliDumpPrintf(dumpMask, equalsDefault, formatUnassigned, owner);
}
} else {
cliDumpPrintf(dumpMask, equalsDefault, format, owner, IO_GPIOPortIdx(io) + 'A', IO_GPIOPinIdx(io));
}
}
}
}
static void cliResource(char *cmdline)
{
int len;
len = strlen(cmdline);
int len = strlen(cmdline);
if (len == 0) {
cliPrintf("IO:\r\n----------------------\r\n");
printResource(DUMP_MASTER | HIDE_UNUSED, NULL);
return;
} else if (strncasecmp(cmdline, "list", len) == 0) {
#ifndef CLI_MINIMAL_VERBOSITY
cliPrintf("Currently active IO resource assignments:\r\n(reboot to update)\r\n----------------------\r\n");
#endif
for (uint32_t i = 0; i < DEFIO_IO_USED_COUNT; i++) {
const char* owner;
owner = ownerNames[ioRecs[i].owner];
@ -3772,34 +3838,10 @@ static void cliResource(char *cmdline)
cliPrintf("%c%02d: %s %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, resource);
}
}
cliPrintf("\r\nUse: 'resource list' to see how to change resources.\r\n");
return;
} else if (strncasecmp(cmdline, "list", len) == 0) {
for (uint8_t i = 0; i < ARRAYLEN(resourceTable); i++) {
const char* owner;
owner = ownerNames[resourceTable[i].owner];
#ifndef CLI_MINIMAL_VERBOSITY
cliPrintf("\r\nUse: 'resource' to see how to change resources.\r\n");
#endif
if (resourceTable[i].maxIndex > 0) {
for (int index = 0; index < resourceTable[i].maxIndex; index++) {
if (DEFIO_TAG_ISEMPTY(*(resourceTable[i].ptr + index))) {
continue;
}
IO_t io = IOGetByTag(*(resourceTable[i].ptr + index));
if (!io) {
continue;
}
cliPrintf("resource %s %d %c%02d\r\n", owner, RESOURCE_INDEX(index), IO_GPIOPortIdx(io) + 'A', IO_GPIOPinIdx(io));
}
} else {
if (DEFIO_TAG_ISEMPTY(*(resourceTable[i].ptr))) {
continue;
}
IO_t io = IOGetByTag(*resourceTable[i].ptr);
cliPrintf("resource %s %c%02d\r\n", owner, IO_GPIOPortIdx(io) + 'A', IO_GPIOPinIdx(io));
}
}
return;
}
@ -3840,7 +3882,11 @@ static void cliResource(char *cmdline)
cliPrintf("Resource is freed!");
return;
} else {
uint8_t port = (*pch)-'A';
uint8_t port = (*pch) - 'A';
if (port >= 8) {
port = (*pch) - 'a';
}
if (port < 8) {
pch++;
pin = atoi(pch);
@ -3865,7 +3911,9 @@ static void cliResource(char *cmdline)
void cliDfu(char *cmdLine)
{
UNUSED(cmdLine);
#ifndef CLI_MINIMAL_VERBOSITY
cliPrint("\r\nRestarting in DFU mode");
#endif
cliRebootEx(true);
}

View file

@ -293,6 +293,7 @@ static void saProcessResponse(uint8_t *buf, int len)
// Export current settings for CMS
#ifdef CMS
smartAudioBand = (sa_chan / 8) + 1;
smartAudioChan = (sa_chan % 8) + 1;
smartAudioFreq = saFreqTable[sa_chan / 8][sa_chan % 8];
@ -312,6 +313,7 @@ static void saProcessResponse(uint8_t *buf, int len)
} else {
smartAudioPower = saDacToPowerIndex(sa_power) + 1;
}
#endif
#ifdef SMARTAUDIO_DEBUG_MONITOR
debug[0] = sa_vers * 100 + sa_opmode;
@ -342,7 +344,9 @@ static void saProcessResponse(uint8_t *buf, int len)
if (freq & SA_FREQ_GETPIT) {
sa_pitfreq = freq & ~SA_FREQ_GETPIT;
dprintf(("saProcessResponse: GETPIT freq %d\r\n", sa_pitfreq));
#ifdef CMS
smartAudioUpdateStatusString();
#endif
} else if (freq & SA_FREQ_SETPIT) {
dprintf(("saProcessResponse: SETPIT freq %d\r\n", freq));
} else {
@ -844,5 +848,108 @@ long smartAudioConfigureOpModelByGvar(displayPort_t *pDisp, void *self)
return 0;
}
static const char * const smartAudioBandNames[] = {
"--------",
"BOSCAM A",
"BOSCAM B",
"BOSCAM E",
"FATSHARK",
"RACEBAND",
};
OSD_TAB_t entrySmartAudioBand = { &smartAudioBand, 5, &smartAudioBandNames[0], NULL };
static const char * const smartAudioChanNames[] = {
"-", "1", "2", "3", "4", "5", "6", "7", "8",
};
OSD_TAB_t entrySmartAudioChan = { &smartAudioChan, 8, &smartAudioChanNames[0], NULL };
static const char * const smartAudioPowerNames[] = {
"---",
" 25",
"200",
"500",
"800",
};
OSD_TAB_t entrySmartAudioPower = { &smartAudioPower, 4, &smartAudioPowerNames[0]};
static const char * const smartAudioTxModeNames[] = {
"------",
"PIT-OR",
"PIT-IR",
"ACTIVE",
};
OSD_TAB_t entrySmartAudioTxMode = { &smartAudioTxMode, 3, &smartAudioTxModeNames[0]};
OSD_UINT16_t entrySmartAudioFreq = { &smartAudioFreq, 5600, 5900, 0 };
static const char * const smartAudioOpModelNames[] = {
"FREE",
"PIT",
};
OSD_TAB_t entrySmartAudioOpModel = { &smartAudioOpModel, 1, &smartAudioOpModelNames[0] };
static const char * const smartAudioPitFModeNames[] = {
"IN-RANGE",
"OUT-RANGE",
};
OSD_TAB_t entrySmartAudioPitFMode = { &smartAudioPitFMode, 1, &smartAudioPitFModeNames[0] };
OSD_UINT16_t entrySmartAudioORFreq = { &smartAudioORFreq, 5600, 5900, 1 };
OSD_Entry menu_smartAudioConfig[] = {
{ "--- SMARTAUDIO CONFIG ---", OME_Label, NULL, NULL, 0 },
{ "OP MODEL", OME_TAB, smartAudioConfigureOpModelByGvar, &entrySmartAudioOpModel, 0 },
{ "PIT FREQ", OME_TAB, smartAudioConfigurePitFModeByGvar, &entrySmartAudioPitFMode, 0 },
{ "OR FREQ", OME_UINT16, NULL, &entrySmartAudioORFreq, 0 }, // OME_Poll_UINT16
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
static const char * const smartAudioStatusNames[] = {
"OFFLINE",
"ONLINE V1",
"ONLINE V2",
};
OSD_TAB_t entrySmartAudioOnline = { &smartAudioStatus, 2, &smartAudioStatusNames[0] };
OSD_UINT16_t entrySmartAudioBaudrate = { &smartAudioSmartbaud, 0, 0, 0 };
OSD_UINT16_t entrySmartAudioStatBadpre = { &saerr_badpre, 0, 0, 0 };
OSD_UINT16_t entrySmartAudioStatBadlen = { &saerr_badlen, 0, 0, 0 };
OSD_UINT16_t entrySmartAudioStatCrcerr = { &saerr_crcerr, 0, 0, 0 };
OSD_UINT16_t entrySmartAudioStatOooerr = { &saerr_oooresp, 0, 0, 0 };
OSD_Entry menu_smartAudioStats[] = {
{ "--- SMARTAUDIO STATS ---", OME_Label, NULL, NULL, 0 },
{ "STATUS", OME_TAB, NULL, &entrySmartAudioOnline, 0 },
{ "BAUDRATE", OME_UINT16, NULL, &entrySmartAudioBaudrate, 0 },
{ "BADPRE", OME_UINT16, NULL, &entrySmartAudioStatBadpre, 0 },
{ "BADLEN", OME_UINT16, NULL, &entrySmartAudioStatBadlen, 0 },
{ "CRCERR", OME_UINT16, NULL, &entrySmartAudioStatCrcerr, 0 },
{ "OOOERR", OME_UINT16, NULL, &entrySmartAudioStatOooerr, 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
OSD_Entry cmsx_menuVtxSmartAudio[] =
{
{ "-- VTX SMARTAUDIO --", OME_Label, NULL, NULL, 0 },
{ smartAudioStatusString, OME_Label, NULL, NULL, 0 },
{ "TXMODE", OME_TAB, smartAudioSetTxModeByGvar, &entrySmartAudioTxMode, 0 },
{ "BAND", OME_TAB, smartAudioConfigureBandByGvar, &entrySmartAudioBand, 0 },
{ "CHAN", OME_TAB, smartAudioConfigureChanByGvar, &entrySmartAudioChan, 0 },
{ "FREQ", OME_UINT16, NULL, &entrySmartAudioFreq, 0 },
{ "POWER", OME_TAB, smartAudioConfigurePowerByGvar, &entrySmartAudioPower, 0 },
{ "CONFIG", OME_Submenu, cmsMenuChange, &menu_smartAudioConfig[0], 0 },
{ "STAT", OME_Submenu, cmsMenuChange, &menu_smartAudioStats[0], 0 },
{ "BACK", OME_Back, NULL, NULL, 0 },
{ NULL, OME_END, NULL, NULL, 0 }
};
#endif // CMS
#endif // VTX_SMARTAUDIO

View file

@ -33,4 +33,6 @@ long smartAudioConfigureBandByGvar(displayPort_t *, void *self);
long smartAudioConfigureChanByGvar(displayPort_t *, void *self);
long smartAudioConfigurePowerByGvar(displayPort_t *, void *self);
long smartAudioSetTxModeByGvar(displayPort_t *, void *self);
extern OSD_Entry cmsx_menuVtxSmartAudio[];
#endif

View file

@ -75,6 +75,7 @@
#include "rx/spektrum.h"
#include "io/cms.h"
#include "io/cms_types.h"
#include "io/beeper.h"
#include "io/serial.h"
@ -84,7 +85,7 @@
#include "io/servos.h"
#include "io/gimbal.h"
#include "io/ledstrip.h"
#include "io/display.h"
#include "io/dashboard.h"
#include "io/asyncfatfs/asyncfatfs.h"
#include "io/serial_cli.h"
#include "io/transponder_ir.h"
@ -403,9 +404,9 @@ void init(void)
cmsInit();
#endif
#ifdef DISPLAY
if (feature(FEATURE_DISPLAY)) {
displayInit(&masterConfig.rxConfig);
#ifdef USE_DASHBOARD
if (feature(FEATURE_DASHBOARD)) {
dashboardInit(&masterConfig.rxConfig);
}
#endif
@ -603,13 +604,13 @@ void init(void)
if (feature(FEATURE_VBAT | FEATURE_CURRENT_METER))
batteryInit(&masterConfig.batteryConfig);
#ifdef DISPLAY
if (feature(FEATURE_DISPLAY)) {
#ifdef USE_DASHBOARD
if (feature(FEATURE_DASHBOARD)) {
#ifdef USE_OLED_GPS_DEBUG_PAGE_ONLY
displayShowFixedPage(PAGE_GPS);
dashboardShowFixedPage(PAGE_GPS);
#else
displayResetPageCycling();
displayEnablePageCycling();
dashboardResetPageCycling();
dashboardEnablePageCycling();
#endif
}
#endif

View file

@ -84,18 +84,18 @@
#include "io/servos.h"
#include "io/gimbal.h"
#include "io/ledstrip.h"
#include "io/display.h"
#include "io/dashboard.h"
#include "io/asyncfatfs/asyncfatfs.h"
#include "io/serial_cli.h"
#include "io/transponder_ir.h"
#include "io/cms.h"
#include "io/osd.h"
#include "io/vtx.h"
<<<<<<< HEAD
#include "io/vtx.h"
#include "io/vtx_smartaudio.h"
=======
#include "io/canvas.h"
>>>>>>> bfdev-osd-cms-separation-poc
#include "io/canvas.h"
#include "io/vtx.h"
#include "scheduler/scheduler.h"
@ -407,9 +407,9 @@ void init(void)
cmsInit();
#endif
#ifdef DISPLAY
if (feature(FEATURE_DISPLAY)) {
displayInit(&masterConfig.rxConfig);
#ifdef USE_DASHBOARD
if (feature(FEATURE_DASHBOARD)) {
dashboardInit(&masterConfig.rxConfig);
}
#endif
@ -607,13 +607,13 @@ void init(void)
if (feature(FEATURE_VBAT | FEATURE_CURRENT_METER))
batteryInit(&masterConfig.batteryConfig);
#ifdef DISPLAY
if (feature(FEATURE_DISPLAY)) {
#ifdef USE_DASHBOARD
if (feature(FEATURE_DASHBOARD)) {
#ifdef USE_OLED_GPS_DEBUG_PAGE_ONLY
displayShowFixedPage(PAGE_GPS);
dashboardShowFixedPage(PAGE_GPS);
#else
displayResetPageCycling();
displayEnablePageCycling();
dashboardResetPageCycling();
dashboardEnablePageCycling();
#endif
}
#endif

View file

@ -211,8 +211,6 @@ void mspSerialInit(void)
mspSerialAllocatePorts();
}
mspPushCommandFnPtr mspPushCommandFn;
void mspSerialPush(uint8_t cmd, uint8_t *data, int datalen)
{
static uint8_t pushBuf[30];
@ -234,7 +232,7 @@ void mspSerialPush(uint8_t cmd, uint8_t *data, int datalen)
continue;
}
mspPushCommandFn(&push, data, datalen);
sbufWriteData(&push.buf, data, datalen);
sbufSwitchToReader(&push.buf, pushBuf);
@ -242,7 +240,27 @@ void mspSerialPush(uint8_t cmd, uint8_t *data, int datalen)
}
}
void mspSerialPushInit(mspPushCommandFnPtr mspPushCommandFnToUse)
uint32_t mspSerialTxBytesFree()
{
mspPushCommandFn = mspPushCommandFnToUse;
uint32_t minroom = UINT16_MAX;
for (uint8_t portIndex = 0; portIndex < MAX_MSP_PORT_COUNT; portIndex++) {
mspPort_t * const mspPort = &mspPorts[portIndex];
if (!mspPort->port) {
continue;
}
// XXX Kludge!!! Avoid zombie VCP port (avoid VCP entirely for now)
if (mspPort->port->identifier == SERIAL_PORT_USB_VCP) {
continue;
}
uint32_t room = serialTxBytesFree(mspPort->port);
if (room < minroom) {
minroom = room;
}
}
return minroom;
}

View file

@ -66,5 +66,5 @@ void mspSerialInit(void);
void mspSerialProcess(mspEvaluateNonMspData_e evaluateNonMspData, mspProcessCommandFnPtr mspProcessCommandFn);
void mspSerialAllocatePorts(void);
void mspSerialReleasePortIfAllocated(struct serialPort_s *serialPort);
void mspSerialPushInit(mspPushCommandFnPtr mspPushCommandFn);
void mspSerialPush(uint8_t, uint8_t *, int);
void mspSerialPush(uint8_t cmd, uint8_t *data, int datalen);
uint32_t mspSerialTxBytesFree(void);

View file

@ -67,8 +67,8 @@ typedef enum {
#if defined(BARO) || defined(SONAR)
TASK_ALTITUDE,
#endif
#ifdef DISPLAY
TASK_DISPLAY,
#ifdef USE_DASHBOARD
TASK_DASHBOARD,
#endif
#ifdef TELEMETRY
TASK_TELEMETRY,

View file

@ -24,16 +24,16 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// PPM / UART2 RX
{ TIM8, IO_TAG(PA15), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PPM
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM3
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM4
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // UART3_TX (AF7)
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // UART3_RX (AF7)
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, //LED_STRIP
{ TIM8, IO_TAG(PA15), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_2 }, // PPM
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM1
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM3
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM4
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM8
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // UART3_TX (AF7)
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // UART3_RX (AF7)
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6 }, //LED_STRIP
};

View file

@ -23,13 +23,13 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 - PA4 - *TIM3_CH2
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM1 - PA4 - *TIM3_CH2
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_PPM, 0, GPIO_AF_1 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
};

View file

@ -89,7 +89,6 @@
#define SENSORS_SET (SENSOR_ACC)
#undef GPS
#define DISPLAY
#define USE_FLASHFS
#define USE_FLASH_M25P16

View file

@ -23,19 +23,18 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6}, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_11}, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2} // PWM14 - OUT6
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PPM | TIM_USE_PWM, 0, GPIO_AF_1}, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1}, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1}, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1}, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2}, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2}, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2}, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2}, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6}, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_11}, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2} // PWM14 - OUT6
};

View file

@ -23,19 +23,19 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD } // PWM14 - OUT6
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0 }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 0 } // PWM14 - OUT6
};

View file

@ -24,18 +24,16 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// up to 10 Motor Outputs
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
// PPM PORT - Also USART2 RX (AF5)
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
};

View file

@ -23,19 +23,18 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // PWM1 - PA8 RC1
{ TIM1, IO_TAG(PB0), TIM_Channel_2, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // PWM2 - PB0 RC2
{ TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // PWM3 - PB1 RC3
{ TIM8, IO_TAG(PB14),TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PWM4 - PA14 RC4
{ TIM8, IO_TAG(PB15),TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PWM5 - PA15 RC5
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // PWM6 - PB8 OUT1
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // PWM7 - PB9 OUT2
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // PWM8 - PA0 OUT3
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // PWM9 - PA1 OUT4
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM10 - PC6 OUT5
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM11 - PC7 OUT6
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM13 - PC8 OUT7
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // PWM13 - PC9 OUT8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM1 }, // PWM1 - PA8 RC1
{ TIM1, IO_TAG(PB0), TIM_Channel_2, TIM1_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // PWM2 - PB0 RC2
{ TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM1 }, // PWM3 - PB1 RC3
{ TIM8, IO_TAG(PB14),TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // PWM4 - PA14 RC4
{ TIM8, IO_TAG(PB15),TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // PWM5 - PA15 RC5
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // PWM6 - PB8 OUT1
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // PWM7 - PB9 OUT2
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // PWM8 - PA0 OUT3
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // PWM9 - PA1 OUT4
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM10 - PC6 OUT5
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM11 - PC7 OUT6
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM13 - PC8 OUT7
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // PWM13 - PC9 OUT8
};

View file

@ -26,44 +26,44 @@
#if defined(USE_DSHOT)
// DSHOT TEST
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP , GPIO_AF9_TIM12, NULL, 0, 0 }, // S1_IN
{ TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP , GPIO_AF9_TIM12, NULL, 0, 0 }, // S2_IN
{ TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8, NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8, NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8, NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8, NULL, 0, 0 }, // S6_IN
{ TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PPM | TIM_USE_PWM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S1_IN
{ TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S2_IN
{ TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S6_IN
{ TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM4_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM4, DMA1_Stream7, DMA_CHANNEL_2, DMA1_ST7_HANDLER }, // S10_OUT 1
{ TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM2_IRQn, 1, IOCFG_AF_PP , GPIO_AF1_TIM2, DMA1_Stream1, DMA_CHANNEL_3, DMA1_ST1_HANDLER }, // S6_OUT 2
{ TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM2_IRQn, 1, IOCFG_AF_PP , GPIO_AF1_TIM2, DMA1_Stream6, DMA_CHANNEL_3, DMA1_ST6_HANDLER }, // S1_OUT 4
{ TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM5_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM5, DMA1_Stream4, DMA_CHANNEL_6, DMA1_ST4_HANDLER }, // S2_OUT
{ TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM3_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM3, DMA1_Stream5, DMA_CHANNEL_5, DMA1_ST5_HANDLER }, // S4_OUT
{ TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM5_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM5, DMA1_Stream2, DMA_CHANNEL_6, DMA1_ST2_HANDLER }, // S7_OUT
{ TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM4_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM4, NULL, 0, 0 }, // S5_OUT 3
{ TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP , GPIO_AF3_TIM9, NULL, 0, 0 }, // S3_OUT
{ TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM2_IRQn, 1, IOCFG_AF_PP , GPIO_AF1_TIM2, NULL, 0, 0 }, // S8_OUT
{ TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM3_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM3, NULL, 0, 0 }, // S9_OUT
{ TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, DMA1_Stream7, DMA_CHANNEL_2, DMA1_ST7_HANDLER }, // S10_OUT 1
{ TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, DMA1_Stream1, DMA_CHANNEL_3, DMA1_ST1_HANDLER }, // S6_OUT 2
{ TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, DMA1_Stream6, DMA_CHANNEL_3, DMA1_ST6_HANDLER }, // S1_OUT 4
{ TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5, DMA1_Stream4, DMA_CHANNEL_6, DMA1_ST4_HANDLER }, // S2_OUT
{ TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, DMA1_Stream5, DMA_CHANNEL_5, DMA1_ST5_HANDLER }, // S4_OUT
{ TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5, DMA1_Stream2, DMA_CHANNEL_6, DMA1_ST2_HANDLER }, // S7_OUT
{ TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, NULL, 0, 0 }, // S5_OUT 3
{ TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM1_BRK_TIM9_IRQn, TIM_USE_MOTOR, 1, GPIO_AF3_TIM9, NULL, 0, 0 }, // S3_OUT
{ TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, NULL, 0, 0 }, // S8_OUT
{ TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, NULL, 0, 0 }, // S9_OUT
};
#else
// STANDARD LAYOUT
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP , GPIO_AF9_TIM12}, // S1_IN
{ TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP , GPIO_AF9_TIM12}, // S2_IN
{ TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8}, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8}, // S4_IN
{ TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8}, // S5_IN
{ TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8}, // S6_IN
{ TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF9_TIM12}, // S1_IN
{ TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF9_TIM12}, // S2_IN
{ TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8}, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8}, // S4_IN
{ TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8}, // S5_IN
{ TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF3_TIM8}, // S6_IN
{ TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM4_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM4}, // S10_OUT 1
{ TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM2_IRQn, 1, IOCFG_AF_PP , GPIO_AF1_TIM2}, // S6_OUT 2
{ TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM4_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM4}, // S5_OUT 3
{ TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM2_IRQn, 1, IOCFG_AF_PP , GPIO_AF1_TIM2}, // S1_OUT 4
{ TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM5_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM5}, // S2_OUT
{ TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP , GPIO_AF3_TIM9}, // S3_OUT
{ TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM3_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM3}, // S4_OUT
{ TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM5_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM5}, // S7_OUT
{ TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM2_IRQn, 1, IOCFG_AF_PP , GPIO_AF1_TIM2}, // S8_OUT
{ TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM3_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM3}, // S9_OUT
{ TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4}, // S10_OUT 1
{ TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2}, // S6_OUT 2
{ TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4}, // S5_OUT 3
{ TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2}, // S1_OUT 4
{ TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5}, // S2_OUT
{ TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM1_BRK_TIM9_IRQn, TIM_USE_MOTOR, 1, GPIO_AF3_TIM9}, // S3_OUT
{ TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3}, // S4_OUT
{ TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5}, // S7_OUT
{ TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2}, // S8_OUT
{ TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3}, // S9_OUT
};
#endif

View file

@ -24,17 +24,17 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PB7), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // RC PPM - PB7 - TIM17_CH1N AF1, TIM4_CH2 AF2, TIM8_BKIN AF5, TIM3_CH4 AF10
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel1, DMA1_CH1_HANDLER }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM8, IO_TAG(PB8), TIM_Channel_2, TIM8_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10,DMA2_Channel5, DMA2_CH5_HANDLER }, // PWM3 - PB8
{ TIM8, IO_TAG(PB9), TIM_Channel_3, TIM8_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10,DMA2_Channel1, DMA2_CH1_HANDLER }, // PWM4 - PB9
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // PWM5 - PA1
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // PWM6 - PA0
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, NULL, 0 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, NULL, 0 }, // PWM8 - PA3
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM1 - PA6 - TIM3_CH1 AF2, TIM8_BKIN AF4, TIM1_BKIN AF6, *TIM16_CH1 AF1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM2 - PA7 - TIM3_CH2 AF2, TIM8_CH1 AF4, TIM1_CH1N AF6, *TIM17_CH1 AF1
{ TIM8, IO_TAG(PB8), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10,DMA2_Channel5, DMA2_CH5_HANDLER }, // PWM3 - PB8 - TIM16_CH1 AF1, TIM4_CH3 AF2, TIM8_CH2 AF10, TIM1_BKIN AF12
{ TIM8, IO_TAG(PB9), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA2_Channel2, DMA2_CH2_HANDLER }, // PWM4 - PB9 - TIM17_CH1 AF1, TIM4_CH4 AF2, TIM8_CH3 AF10
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // SOFTSERIAL RX - TIM3_CH3 AF2, TIM8_CH2N AF4, TIM1_CH2N AF6
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // SOFTSERIAL TX - TIM3_CH4 AF2, TIM8_CH3N AF4, TIM1_CH3N AF6
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PA0 - TIM2_CH1 AF1, TIM8_BKIN AF9, TIM8_ETR AF10
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7 - PA2 - TIM2_CH3 AF1, TIM15_CH1 AF9
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, NULL, 0 }, // GPIO_TIMER / LED_STRIP
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, NULL, 0 }, // GPIO_TIMER / LED_STRIP
};

View file

@ -45,11 +45,8 @@
#define USE_EXTI
#define USE_DSHOT
// UART1 TX uses DMA1_Channel4, which is also used by dshot on motor 4
#if defined(USE_UART1_TX_DMA) && defined(USE_DSHOT)
#undef USE_UART1_TX_DMA
#endif
#define REMAP_TIM16_DMA
#define REMAP_TIM17_DMA
#define USB_IO
@ -66,11 +63,11 @@
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
#define UART2_TX_PIN PA2 // PA14 / SWCLK
#define UART2_TX_PIN PA2
#define UART2_RX_PIN PA3
#define UART3_TX_PIN PB10 // PB10 (AF7)
#define UART3_RX_PIN PB11 // PB11 (AF7)
#define UART3_TX_PIN PB10
#define UART3_RX_PIN PB11
#define SOFTSERIAL_2_TIMER TIM3
#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 5
@ -81,7 +78,6 @@
#define USE_SPI
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
//GPIO_AF_1
#define SPI1_NSS_PIN PA15
#define SPI1_SCK_PIN PB3

View file

@ -23,12 +23,12 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // PPM IN
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, DMA1_Stream2, DMA_Channel_6, DMA1_ST2_HANDLER }, // S1_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, DMA1_Stream4, DMA_Channel_6, DMA1_ST4_HANDLER }, // S2_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S3_OUT
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S4_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S5_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S6_OUT
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // PPM IN
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, DMA1_Stream2, DMA_Channel_6, DMA1_ST2_HANDLER }, // S1_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, DMA1_Stream4, DMA_Channel_6, DMA1_ST4_HANDLER }, // S2_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S3_OUT
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S4_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S5_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S6_OUT
};

View file

@ -23,17 +23,17 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // S1_IN
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / Sonar trigger
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // S4_IN - Current
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // S5_IN - Vbattery
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // S6_IN - PPM IN
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP }, // S1_OUT
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP }, // S2_OUT
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP }, // S3_OUT
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP }, // S4_OUT
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP }, // S5_OUT - GPIO_PartialRemap_TIM3 - LED Strip
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP } // S6_OUT
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_PWM, 0, }, // S1_IN
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, }, // S2_IN - SoftSerial TX - GPIO_PartialRemap_TIM3 / Sonar trigger
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, }, // S3_IN - SoftSerial RX / Sonar echo / RSSI ADC
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, }, // S4_IN - Current
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM, 0, }, // S5_IN - Vbattery
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, }, // S6_IN - PPM IN
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, }, // S1_OUT
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, }, // S2_OUT
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, }, // S3_OUT
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, }, // S4_OUT
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, }, // S5_OUT - GPIO_PartialRemap_TIM3 - LED Strip
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, } // S6_OUT
};

View file

@ -24,23 +24,23 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// INPUTS CH1-8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_6 }, // PWM1 - PA8
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM2 - PB8
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM3 - PB9
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4 }, // PWM4 - PC6
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4 }, // PWM5 - PC7
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_4 }, // PWM6 - PC8
{ TIM15, IO_TAG(PF9), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_3 }, // PWM7 - PF9
{ TIM15, IO_TAG(PF10), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_3 }, // PWM8 - PF10
{ TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM9 - PD12
{ TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM10 - PD13
{ TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM11 - PD14
{ TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM12 - PD15
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM13 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM14 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM15 - PA3
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM16 - PB0
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM17 - PB1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 } // PWM18 - PA4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM1 - PA8
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM2 - PB8
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM3 - PB9
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4 }, // PWM4 - PC6
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4 }, // PWM5 - PC7
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_4 }, // PWM6 - PC8
{ TIM15, IO_TAG(PF9), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_PWM, 0, GPIO_AF_3 }, // PWM7 - PF9
{ TIM15, IO_TAG(PF10), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_PWM, 0, GPIO_AF_3 }, // PWM8 - PF10
{ TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM9 - PD12
{ TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM10 - PD13
{ TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM11 - PD14
{ TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM12 - PD15
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM13 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM14 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM15 - PA3
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM16 - PB0
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM17 - PB1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 } // PWM18 - PA4
};

View file

@ -23,19 +23,19 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD } // PWM14 - OUT6
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11),TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 0 } // PWM14 - OUT6
};

View file

@ -24,21 +24,20 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM1 }, // S1_IN
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S2_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S3_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S4_IN
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S5_IN
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S6_IN
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S7_IN
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S8_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S1_OUT
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S2_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S3_OUT
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM12 }, // S4_OUT
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S5_OUT
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM12 }, // S6_OUT
{ TIM10, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM10_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM10 }, // S7_OUT
{ TIM11, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM11_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM11 }, // S8_OUT
{ TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM1 }, // S1_IN
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S2_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S3_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S4_IN
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM2 }, // S5_IN
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM2 }, // S6_IN
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM5 }, // S7_IN
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM5 }, // S8_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S1_OUT
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S2_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S3_OUT
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM12 }, // S4_OUT
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S5_OUT
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM12 }, // S6_OUT
{ TIM10, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM10_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM10 }, // S7_OUT
{ TIM11, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM11_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM11 }, // S8_OUT
};

View file

@ -23,16 +23,16 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6 }, // PWM1 - PA8
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PC6
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PC7
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PMW4 - PC8
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PC9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PA3
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM10 - PB14
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM11 - PB15
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_6 }, // PWM1 - PA8
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PC6
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PC7
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PMW4 - PC8
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PC9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM7 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM8 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM9 - PA3
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM10 - PB14
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM11 - PB15
};

View file

@ -23,17 +23,14 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6 }, // PWM1 - PA8
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB9
{ TIM2, IO_TAG(PA10), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PMW4 - PA10
{ TIM2, IO_TAG(PA9), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PWM5 - PA9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - PA1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PWM8 - PB1
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PWM9 - PB0
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_6 }, // PWM1 - PA8
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PB9
{ TIM2, IO_TAG(PA10), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 }, // PMW4 - PA10
{ TIM2, IO_TAG(PA9), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 }, // PWM5 - PA9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM7 - PA1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM8 - PB1
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM9 - PB0
};

View file

@ -6,24 +6,22 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S1_IN
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S2_IN
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S3_IN
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3}, // S4_IN
{ TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S5_IN
{ TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S6_IN
{ TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S7_IN
{ TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM4}, // S8_IN
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2}, // S1_OUT
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2}, // S2_OUT
{ TIM5, IO_TAG(PA2), TIM_Channel_3, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5}, // S3_OUT
{ TIM5, IO_TAG(PA3), TIM_Channel_4, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5}, // S4_OUT
{ TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S5_OUT
{ TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S6_OUT
{ TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S7_OUT
{ TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S8_OUT
{ TIM9, IO_TAG(PE6), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // sonar echo if needed
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S1_IN
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S2_IN
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S3_IN
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S4_IN
{ TIM4, IO_TAG(PD15), TIM_Channel_4, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S5_IN
{ TIM4, IO_TAG(PD14), TIM_Channel_3, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S6_IN
{ TIM4, IO_TAG(PD13), TIM_Channel_2, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S7_IN
{ TIM4, IO_TAG(PD12), TIM_Channel_1, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM4 }, // S8_IN
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S1_OUT
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S2_OUT
{ TIM5, IO_TAG(PA2), TIM_Channel_3, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S3_OUT
{ TIM5, IO_TAG(PA3), TIM_Channel_4, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S4_OUT
{ TIM1, IO_TAG(PE9), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S5_OUT
{ TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S6_OUT
{ TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S7_OUT
{ TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S8_OUT
{ TIM9, IO_TAG(PE6), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_TIM9 }, // sonar echo if needed
};

View file

@ -25,16 +25,13 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // PPM IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_6, NULL, 0 }, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM3, IO_TAG(PB7), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM4 - S1
{ TIM8, IO_TAG(PB6), TIM_Channel_1, TIM8_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_5, DMA2_Channel3, DMA2_CH3_HANDLER }, // PWM5 - S2
{ TIM8, IO_TAG(PB5), TIM_Channel_3, TIM8_CC_IRQn, (1 | TIMER_OUTPUT_N_CHANNEL), IOCFG_AF_PP, GPIO_AF_3, DMA2_Channel1, DMA2_CH1_HANDLER }, // PWM6 - S3
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM7 - S4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, NULL, 0 }, // GPIO TIMER - LED_STRIP
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // PPM IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // SS1 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM1, IO_TAG(PB1), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_6, NULL, 0 }, // SS1 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM3, IO_TAG(PB7), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM4 - S1
{ TIM8, IO_TAG(PB6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_5, DMA2_Channel3, DMA2_CH3_HANDLER }, // PWM5 - S2
{ TIM8, IO_TAG(PB5), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, (1 | TIMER_OUTPUT_N_CHANNEL), GPIO_AF_3, DMA2_Channel1, DMA2_CH1_HANDLER }, // PWM6 - S3
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM7 - S4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, NULL, 0 }, // GPIO TIMER - LED_STRIP
};

View file

@ -24,12 +24,11 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // PPM_IN
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S1_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S2_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // PPM_IN
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S1_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S2_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT
// { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5 }, // LED Strip
};

View file

@ -22,13 +22,13 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PPM/SERIAL RX
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM2
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM3
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2}, // PWM4
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, // PWM5
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, // PWM6
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6}, // LED_STRIP
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, TIM_USE_PPM, 0, GPIO_AF_1}, // PPM/SERIAL RX
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2}, // PWM1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2}, // PWM2
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2}, // PWM3
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2}, // PWM4
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1}, // PWM5
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1}, // PWM6
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6}, // LED_STRIP
};

View file

@ -23,22 +23,22 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 },// PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 },// PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 },// PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 },// PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
};

View file

@ -23,25 +23,24 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM |TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
// Production boards swapped RC_CH3/4 swapped to make it easier to use SerialRX using supplied cables - compared to first prototype.
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 },// PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 },// PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM8 - PA3
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 },// PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 },// PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
};

View file

@ -24,18 +24,18 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM15, IO_TAG(PB15), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIMER_OUTPUT_ENABLED, IOCFG_AF_PP, GPIO_AF_6, DMA1_Channel5, DMA1_CH5_HANDLER },
{ TIM8, IO_TAG(PB0), TIM_Channel_2, TIM8_CC_IRQn, TIMER_OUTPUT_ENABLED, IOCFG_AF_PP, GPIO_AF_2, DMA2_Channel5, DMA2_CH5_HANDLER },
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIMER_OUTPUT_ENABLED|TIMER_OUTPUT_INVERTED, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel2, DMA1_CH2_HANDLER },
{ TIM1, IO_TAG(PB14), TIM_Channel_2, TIM1_CC_IRQn, TIMER_OUTPUT_ENABLED, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER },
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIMER_OUTPUT_ENABLED|TIMER_OUTPUT_INVERTED, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel6, DMA1_CH6_HANDLER },
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIMER_OUTPUT_ENABLED|TIMER_OUTPUT_INVERTED, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER },
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER },
{ TIM8, IO_TAG(PB0), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL | TIMER_OUTPUT_INVERTED, GPIO_AF_4, DMA2_Channel5, DMA2_CH5_HANDLER },
{ TIM1, IO_TAG(PB14), TIM_Channel_2, TIM1_CC_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL | TIMER_OUTPUT_INVERTED, GPIO_AF_6, DMA1_Channel3, DMA1_CH3_HANDLER },
{ TIM15, IO_TAG(PB15), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_N_CHANNEL | TIMER_OUTPUT_INVERTED, GPIO_AF_2, DMA1_Channel5, DMA1_CH5_HANDLER },
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, GPIO_AF_2, DMA1_Channel6, DMA1_CH6_HANDLER },
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER },
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0}, // TODO - Cleanup. KISS FC uses the same pin for serial and PPM
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0},
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0},
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0},
{ TIM4, IO_TAG(PA13), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_AF_PP, GPIO_AF_10, NULL, 0},
{ TIM8, IO_TAG(PA14), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_5, NULL, 0},
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0}, // TODO - Cleanup. KISS FC uses the same pin for serial and PPM
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0},
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0},
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0},
//{ TIM4, IO_TAG(PA13), TIM_Channel_2, TIM4_IRQn, TIM_USE_PWM, 0, GPIO_AF_10, NULL, 0},
//{ TIM8, IO_TAG(PA14), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_5, NULL, 0},
};

View file

@ -84,5 +84,5 @@
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTF (BIT(4))
#define USABLE_TIMER_CHANNEL_COUNT 12
#define USABLE_TIMER_CHANNEL_COUNT 10
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17))

View file

@ -23,16 +23,16 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_6 }, // PWM1 - PA8
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PC6
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PC7
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PMW4 - PC8
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PC9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PA3
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM10 - PB14
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PWM11 - PB15
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_6 }, // PWM1 - PA8
{ TIM3, IO_TAG(PC6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PC6
{ TIM3, IO_TAG(PC7), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PC7
{ TIM3, IO_TAG(PC8), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PMW4 - PC8
{ TIM3, IO_TAG(PC9), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PC9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM6 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM7 - PA1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM8 - PA2
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM9 - PA3
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM10 - PB14
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM11 - PB15
};

View file

@ -23,19 +23,19 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 0, IOCFG_IPD }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 0, IOCFG_IPD }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 0, IOCFG_IPD }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 0, IOCFG_IPD } // PWM14 - OUT6
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0 }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 0 }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 0 } // PWM14 - OUT6
};

View file

@ -91,7 +91,6 @@
#undef GPS
#undef USE_SERVOS
#define USE_QUAD_MIXER_ONLY
#define DISPLAY
// IO - assuming all IOs on 48pin package

View file

@ -23,14 +23,14 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 - PA4 - *TIM3_CH2
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM1 - PA4 - *TIM3_CH2
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_PPM, 0, GPIO_AF_1 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
};

View file

@ -91,7 +91,6 @@
#define SENSORS_SET (SENSOR_ACC)
#undef GPS
#define DISPLAY
#define USE_FLASHFS
#define USE_FLASH_M25P16

View file

@ -23,19 +23,19 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_IPD }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_IPD }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_IPD }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_IPD }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_IPD }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_IPD }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_IPD }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_IPD }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_IPD }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_IPD }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_IPD }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_IPD } // PWM14 - OUT6
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PPM | TIM_USE_PWM, 0 }, // PWM1 - RC1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM2 - RC2
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM3 - RC3
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0 }, // PWM4 - RC4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM5 - RC5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM6 - RC6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM7 - RC7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0 }, // PWM8 - RC8
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM9 - OUT1
{ TIM1, IO_TAG(PA11), TIM_Channel_4, TIM1_CC_IRQn, TIM_USE_MOTOR, 1 }, // PWM10 - OUT2
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1 }, // PWM11 - OUT3
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1 }, // PWM12 - OUT4
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1 }, // PWM13 - OUT5
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1 } // PWM14 - OUT6
};

View file

@ -118,8 +118,6 @@
//#define SONAR_TRIGGER_PIN_PWM PB8
//#define SONAR_ECHO_PIN_PWM PB9
//#define DISPLAY
#define USE_UART1
#define USE_UART2
/* only 2 uarts available on the NAZE, add ifdef here if present on other boards */

View file

@ -25,18 +25,18 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// PPM Pad
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // PPM - PB4
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PPM, 0, GPIO_AF_2, NULL, 0 }, // PPM - PB4
// PB5 / TIM3 CH2 is connected to USBPresent
{ TIM8, IO_TAG(PB8), TIM_Channel_2, TIM8_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, DMA2_Channel5, DMA2_CH5_HANDLER }, // PWM1 - PB8
{ TIM8, IO_TAG(PB9), TIM_Channel_3, TIM8_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, DMA2_Channel1, DMA2_CH1_HANDLER }, // PWM2 - PB9
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM3 - PA3
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, DMA1_Channel5, DMA1_CH5_HANDLER }, // PWM4 - PA2
{ TIM8, IO_TAG(PB8), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA2_Channel5, DMA2_CH5_HANDLER }, // PWM1 - PB8
{ TIM8, IO_TAG(PB9), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA2_Channel1, DMA2_CH1_HANDLER }, // PWM2 - PB9
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM3 - PA3
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, DMA1_Channel5, DMA1_CH5_HANDLER }, // PWM4 - PA2
// UART3 RX/TX
//{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // PWM5 - PB10 - TIM2_CH3 / UART3_TX (AF7)
//{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // PWM6 - PB11 - TIM2_CH4 / UART3_RX (AF7)
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // PWM7 - PB7
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // PWM8 - PB6
//{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP
//{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM5 - PB10 - TIM2_CH3 / UART3_TX (AF7)
//{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PB11 - TIM2_CH4 / UART3_RX (AF7)
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM7 - PB7
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM8 - PB6
//{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP
};

View file

@ -92,11 +92,13 @@
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
//#define USE_DASHBOARD
// Configuratoin Menu System
#define CMS
// Use external OSD to run CMS
#define CANVAS
//#define CANVAS
// USE I2C OLED display to run CMS
#define OLEDCMS

View file

@ -13,8 +13,12 @@ TARGET_SRC = \
drivers/transponder_ir.c \
drivers/transponder_ir_stm32f30x.c \
io/transponder_ir.c \
io/vtx_smartaudio.c \
drivers/max7456.c \
io/osd.c \
io/cms.c \
io/canvas.c \
io/vtx_smartaudio.c
io/cms.c \
io/cms_imu.c \
io/cms_blackbox.c \
io/cms_vtx.c \
io/cms_ledstrip.c

View file

@ -15,9 +15,14 @@ TARGET_SRC = \
io/transponder_ir.c \
drivers/max7456.c \
io/osd.c \
io/canvas.c \
io/cms.c \
<<<<<<< HEAD
io/canvas.c \
io/vtx_smartaudio.c
=======
io/cms.c \
io/canvas.c
io/cms_imu.c \
io/cms_blackbox.c \
io/cms_vtx.c \
io/cms_ledstrip.c
>>>>>>> bfdev-osd-cms-separation-poc

View file

@ -24,17 +24,17 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM (5th pin on FlexiIO port)
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN - GPIO_PartialRemap_TIM3
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S6_IN
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM (5th pin on FlexiIO port)
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN - GPIO_PartialRemap_TIM3
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S6_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S2_OUT
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S4_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, NULL, 0, 0 }, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1, NULL, 0, 0 }, // S6_OUT
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S2_OUT
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S4_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, NULL, 0, 0 }, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1, NULL, 0, 0 }, // S6_OUT
};

View file

@ -6,7 +6,12 @@ TARGET_SRC = \
drivers/barometer_ms5611.c \
drivers/compass_hmc5883l.c \
drivers/max7456.c \
io/vtx_smartaudio.c \
io/osd.c \
io/canvas.c \
io/cms.c \
io/canvas.c
io/cms_imu.c \
io/cms_blackbox.c \
io/cms_vtx.c \
io/cms_ledstrip.c

View file

@ -23,14 +23,14 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 - PA4 - *TIM3_CH2
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM1 - PA4 - *TIM3_CH2
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_PPM, 0, GPIO_AF_1 }, // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1
};

View file

@ -23,12 +23,11 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1},
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM2 - PC6
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM3 - PC7
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PMW4 - PC8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM5 - PC9
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PPM, 1, GPIO_AF_1},
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM2 - PC6
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM3 - PC7
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PMW4 - PC8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM5 - PC9
};

View file

@ -24,10 +24,10 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM1 - PA4
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1}, // PWM2 - PA7
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6}, // PWM3 - PA8
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM4 - PB0
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2}, // PWM5 - PB1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1}, // PWM6 - PPM
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM1 - PA4
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1}, // PWM2 - PA7
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6}, // PWM3 - PA8
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM4 - PB0
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2}, // PWM5 - PB1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PPM, 0, GPIO_AF_1}, // PWM6 - PPM
};

View file

@ -130,7 +130,6 @@
#define TELEMETRY
#define SERIAL_RX
#define AUTOTUNE
#define DISPLAY
#define USE_SERVOS
#define USE_CLI

View file

@ -24,16 +24,16 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM (5th pin on FlexiIO port)
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8, NULL, 0, 0 }, // S6_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S2_OUT
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, DMA1_Stream4, DMA_Channel_6, DMA1_ST4_HANDLER }, // S5_OUT
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5, DMA1_Stream2, DMA_Channel_6, DMA1_ST2_HANDLER }, // S6_OUT
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // PPM (5th pin on FlexiIO port)
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM12, NULL, 0, 0 }, // S2_IN
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S4_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S5_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8, NULL, 0, 0 }, // S6_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 1, GPIO_AF_TIM3, DMA1_Stream7, DMA_Channel_5, DMA1_ST7_HANDLER }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3, DMA1_Stream2, DMA_Channel_5, DMA1_ST2_HANDLER }, // S2_OUT
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream6, DMA_Channel_3, DMA1_ST6_HANDLER }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2, DMA1_Stream1, DMA_Channel_3, DMA1_ST1_HANDLER }, // S4_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM5, DMA1_Stream4, DMA_Channel_6, DMA1_ST4_HANDLER }, // S5_OUT
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5, DMA1_Stream2, DMA_Channel_6, DMA1_ST2_HANDLER }, // S6_OUT
};

View file

@ -144,6 +144,3 @@
#define USABLE_TIMER_CHANNEL_COUNT 12
#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) )
#define CMS
#define CANVAS

View file

@ -23,18 +23,18 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM2 }, // PPM
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S2_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S3_IN
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S4_IN
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S5_IN
{ TIM2, IO_TAG(PA5), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S6_IN
{ TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1 }, // S1_OUT
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S2_OUT
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // S3_OUT
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM4 }, // S4_OUT
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S5_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S6_OUT
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM2 }, // PPM
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S2_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S3_IN
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S4_IN
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM3 }, // S5_IN
{ TIM2, IO_TAG(PA5), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM2 }, // S6_IN
{ TIM1, IO_TAG(PA10), TIM_Channel_3, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM1 }, // S1_OUT
{ TIM2, IO_TAG(PB3), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S2_OUT
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // S3_OUT
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM4 }, // S4_OUT
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF_TIM5 }, // S5_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S6_OUT
};

View file

@ -23,22 +23,22 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 }, // PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10 }, // PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
};

View file

@ -23,15 +23,15 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PPM/SERIAL RX
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM5
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // SOFTSERIAL1 RX (NC)
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // SOFTSERIAL1 TX
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // LED_STRIP
{ TIM2, IO_TAG(PA15), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1 }, // PPM/SERIAL RX
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM3
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM4
{ TIM16, IO_TAG(PB8), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM5
{ TIM17, IO_TAG(PB9), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM6
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // SOFTSERIAL1 RX (NC)
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // SOFTSERIAL1 TX
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // LED_STRIP
};

View file

@ -24,15 +24,13 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM1 - PB6
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PB6
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB9
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PB0 - *TIM3_CH3
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 - PB1 - *TIM3_CH4
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)y
{ TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM1 - PB6
{ TIM4, IO_TAG(PB7), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM2 - PB6
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM4 - PB9
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5 - PB0 - *TIM3_CH3
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6 - PB1 - *TIM3_CH4
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PPM, 0, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)y
};

View file

@ -137,6 +137,8 @@
//#define USE_QUAD_MIXER_ONLY
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
#define USE_DASHBOARD
#define OSD
// Configuratoin Menu System

View file

@ -13,5 +13,9 @@ TARGET_SRC = \
drivers/vtx_soft_spi_rtc6705.c \
drivers/max7456.c \
io/osd.c \
io/canvas.c \
io/cms.c \
io/canvas.c
io/cms_imu.c \
io/cms_blackbox.c \
io/cms_vtx.c \
io/cms_ledstrip.c

View file

@ -22,16 +22,16 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12 }, // PPM (5th pin on FlexiIO port)
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12 }, // S2_IN - GPIO_PartialRemap_TIM3
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S4_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S5_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S6_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S2_OUT
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9 }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S4_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S6_OUT
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM12 }, // PPM (5th pin on FlexiIO port)
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM12 }, // S2_IN - GPIO_PartialRemap_TIM3
{ TIM8, IO_TAG(PC6), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S3_IN
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S4_IN
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S5_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S6_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S2_OUT
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM9 }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S4_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S6_OUT
};

View file

@ -24,18 +24,18 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// 6 3-pin headers
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 0, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
// PWM7 - PMW10
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_PWM, 1, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
// PPM PORT - Also USART2 RX (AF5)
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, TIM_USE_PPM, 0, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
};

View file

@ -23,17 +23,16 @@
#include "drivers/timer.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // PPM IN
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12 }, // S2_IN
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM12 }, // S3_IN - GPIO_PartialRemap_TIM3
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S4_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM8 }, // S5_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM3 }, // S2_OUT
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM9 }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM2 }, // S4_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM5 }, // S6_OUT
{ TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_TIM8 }, // PPM IN
{ TIM12, IO_TAG(PB14), TIM_Channel_1, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM12 }, // S2_IN
{ TIM12, IO_TAG(PB15), TIM_Channel_2, TIM8_BRK_TIM12_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM12 }, // S3_IN - GPIO_PartialRemap_TIM3
{ TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S4_IN
{ TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, TIM_USE_PWM, 0, GPIO_AF_TIM8 }, // S5_IN
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S1_OUT
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM3 }, // S2_OUT
{ TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM9 }, // S3_OUT
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM2 }, // S4_OUT
{ TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S5_OUT - GPIO_PartialRemap_TIM3
{ TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_TIM5 }, // S6_OUT
};

View file

@ -24,25 +24,25 @@
#include "drivers/dma.h"
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
// Production boards swapped RC_CH3/4 swapped to make it easier to use SerialRX using supplied cables - compared to first prototype.
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1, NULL, 0 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH1 - PA0 - *TIM2_CH1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
// Production boards swapped RC_CH3/4 swapped to make it easierTIM_USE_MOTOR, to using supplied cables - compared to first prototype.
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_PWM, 0, GPIO_AF_1, NULL, 0 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH5 - PB4 - *TIM3_CH1
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH6 - PB5 - *TIM3_CH2
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_PWM, 0, GPIO_AF_2, NULL, 0 }, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, DMA1_Channel1, DMA1_CH1_HANDLER },// PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10, DMA1_Channel4, DMA1_CH4_HANDLER },// PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2, NULL, 0 }, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, NULL, 0 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9, NULL, 0 }, // PWM8 - PA3
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel3, DMA1_CH3_HANDLER }, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1, DMA1_Channel7, DMA1_CH7_HANDLER }, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
{ TIM4, IO_TAG(PA11), TIM_Channel_1, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA1_Channel1, DMA1_CH1_HANDLER },// PWM3 - PA11
{ TIM4, IO_TAG(PA12), TIM_Channel_2, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_10, DMA1_Channel4, DMA1_CH4_HANDLER },// PWM4 - PA12
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM5 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM6 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM7 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9, NULL, 0 }, // PWM8 - PA3
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6, NULL, 0 }, // GPIO_TIMER / LED_STRIP
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6, NULL, 0 }, // GPIO_TIMER / LED_STRIP
};

View file

@ -140,6 +140,8 @@
#define USABLE_TIMER_CHANNEL_COUNT 17
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
#define USE_DASHBOARD
// Configuratoin Menu System
#define CMS

View file

@ -9,6 +9,10 @@ TARGET_SRC = \
drivers/barometer_bmp280.c \
drivers/compass_ak8975.c \
drivers/compass_hmc5883l.c \
io/canvas.c \
io/cms.c \
io/canvas.c
io/cms_imu.c \
io/cms_blackbox.c \
io/cms_vtx.c \
io/cms_ledstrip.c

View file

@ -24,17 +24,17 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// PPM / UART2 RX
{ TIM8, IO_TAG(PA15), TIM_Channel_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_2 }, // PPM
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM3
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM8
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
{ TIM8, IO_TAG(PA15), TIM_Channel_1, TIM8_CC_IRQn, TIM_USE_PPM, 0, GPIO_AF_2 }, // PPM
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM3
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM4
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM5
{ TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM6
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM7
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM8
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
};

View file

@ -25,27 +25,27 @@
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
// PPM Pad
#ifdef SPRACINGF3MINI_MKII_REVA
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PPM - PB5
{ TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, TIM_USE_PPM, 0, GPIO_AF_2 }, // PPM - PB5
// PB4 / TIM3 CH1 is connected to USBPresent
#else
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PPM - PB4
{ TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, TIM_USE_PPM, 0, GPIO_AF_2 }, // PPM - PB4
// PB5 / TIM3 CH2 is connected to USBPresent
#endif
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PA6
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PA7
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM5 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_9 }, // PWM6 - PA3
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA1
{ TIM16, IO_TAG(PA6), TIM_Channel_1, TIM1_UP_TIM16_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM1 - PA6
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM2 - PA7
{ TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM3 - PB8
{ TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_2 }, // PWM4 - PB9
{ TIM15, IO_TAG(PA2), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM5 - PA2
{ TIM15, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_9 }, // PWM6 - PA3
{ TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM7 - PA0
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, TIM_USE_MOTOR, 1, GPIO_AF_1 }, // PWM8 - PA1
// UART3 RX/TX
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / UART3_TX (AF7)
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / UART3_RX (AF7)
{ TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, 1, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / UART3_TX (AF7)
{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, 1, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / UART3_RX (AF7)
// LED Strip Pad
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, TIM_USE_LED, 1, GPIO_AF_6 }, // GPIO_TIMER / LED_STRIP
};

Some files were not shown because too many files have changed in this diff Show more