Merge pull request #5825 from blckmn/timer_prep

Timer clean up in preparation for configurable timers.
This commit is contained in:
Michael Keller 2018-05-06 12:59:08 +12:00 committed by GitHub
commit 05b6d3d494
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
19 changed files with 125 additions and 87 deletions

View File

@ -32,6 +32,7 @@ COMMON_SRC = \
drivers/sound_beeper.c \
drivers/stack_check.c \
drivers/system.c \
drivers/timer_common.c \
drivers/timer.c \
drivers/transponder_ir_arcitimer.c \
drivers/transponder_ir_ilap.c \

View File

@ -129,7 +129,7 @@ void cameraControlInit(void)
if (CAMERA_CONTROL_MODE_HARDWARE_PWM == cameraControlConfig()->mode) {
#ifdef CAMERA_CONTROL_HARDWARE_PWM_AVAILABLE
const timerHardware_t *timerHardware = timerGetByTag(cameraControlConfig()->ioTag, TIM_USE_ANY);
const timerHardware_t *timerHardware = timerGetByTag(cameraControlConfig()->ioTag);
if (!timerHardware) {
return;

View File

@ -53,7 +53,7 @@ void ws2811LedStripHardwareInit(ioTag_t ioTag)
return;
}
const timerHardware_t *timerHardware = timerGetByTag(ioTag, TIM_USE_ANY);
const timerHardware_t *timerHardware = timerGetByTag(ioTag);
TIM_TypeDef *timer = timerHardware->tim;
timerChannel = timerHardware->channel;

View File

@ -66,7 +66,7 @@ void ws2811LedStripHardwareInit(ioTag_t ioTag)
TIM_OCInitTypeDef TIM_OCInitStructure;
DMA_InitTypeDef DMA_InitStructure;
const timerHardware_t *timerHardware = timerGetByTag(ioTag, TIM_USE_ANY);
const timerHardware_t *timerHardware = timerGetByTag(ioTag);
timer = timerHardware->tim;
if (timerHardware->dmaRef == NULL) {

View File

@ -282,7 +282,7 @@ void motorDevInit(const motorDevConfig_t *motorConfig, uint16_t idlePulse, uint8
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
const ioTag_t tag = motorConfig->ioTags[motorIndex];
const timerHardware_t *timerHardware = timerGetByTag(tag, TIM_USE_ANY);
const timerHardware_t *timerHardware = timerGetByTag(tag);
if (timerHardware == NULL) {
/* not enough motors initialised for the mixer or a break in the motors */
@ -449,7 +449,7 @@ void servoDevInit(const servoDevConfig_t *servoConfig)
IOInit(servos[servoIndex].io, OWNER_SERVO, RESOURCE_INDEX(servoIndex));
const timerHardware_t *timer = timerGetByTag(tag, TIM_USE_ANY);
const timerHardware_t *timer = timerGetByTag(tag);
#if defined(USE_HAL_DRIVER)
IOConfigGPIOAF(servos[servoIndex].io, IOCFG_AF_PP, timer->alternateFunction);
#else
@ -490,7 +490,7 @@ void pwmToggleBeeper(void)
void beeperPwmInit(const ioTag_t tag, uint16_t frequency)
{
const timerHardware_t *timer = timerGetByTag(tag, TIM_USE_BEEPER);
const timerHardware_t *timer = timerGetByTag(tag);
IO_t beeperIO = IOGetByTag(tag);
if (beeperIO && timer) {

View File

@ -371,7 +371,7 @@ void pwmRxInit(const pwmConfig_t *pwmConfig)
pwmInputPort_t *port = &pwmInputPorts[channel];
const timerHardware_t *timer = timerGetByTag(pwmConfig->ioTags[channel], TIM_USE_ANY);
const timerHardware_t *timer = timerGetByTag(pwmConfig->ioTags[channel]);
if (!timer) {
/* TODO: maybe fail here if not enough channels? */
@ -426,7 +426,7 @@ void ppmRxInit(const ppmConfig_t *ppmConfig)
pwmInputPort_t *port = &pwmInputPorts[FIRST_PWM_PORT];
const timerHardware_t *timer = timerGetByTag(ppmConfig->ioTag, TIM_USE_ANY);
const timerHardware_t *timer = timerGetByTag(ppmConfig->ioTag);
if (!timer) {
/* TODO: fail here? */
return;

View File

@ -673,7 +673,7 @@ static serialPort_t *openEscSerial(escSerialPortIndex_e portIndex, serialReceive
}
escSerial->mode = mode;
escSerial->txTimerHardware = timerGetByTag(escSerialConfig()->ioTag, TIM_USE_ANY);
escSerial->txTimerHardware = timerGetByTag(escSerialConfig()->ioTag);
#ifdef USE_HAL_DRIVER
escSerial->txTimerHandle = timerFindTimerHandle(escSerial->txTimerHardware->tim);
@ -952,7 +952,7 @@ void escEnablePassthrough(serialPort_t *escPassthroughPort, uint16_t output, uin
}
else {
uint8_t first_output = 0;
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
for (unsigned i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
if (timerHardware[i].usageFlags & TIM_USE_MOTOR) {
first_output = i;
break;

View File

@ -242,8 +242,8 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
ioTag_t tagRx = serialPinConfig()->ioTagRx[pinCfgIndex];
ioTag_t tagTx = serialPinConfig()->ioTagTx[pinCfgIndex];
const timerHardware_t *timerRx = timerGetByTag(tagRx, TIM_USE_ANY);
const timerHardware_t *timerTx = timerGetByTag(tagTx, TIM_USE_ANY);
const timerHardware_t *timerRx = timerGetByTag(tagRx);
const timerHardware_t *timerTx = timerGetByTag(tagTx);
IO_t rxIO = IOGetByTag(tagRx);
IO_t txIO = IOGetByTag(tagTx);

View File

@ -779,12 +779,12 @@ void timerInit(void)
#endif
/* enable the timer peripherals */
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
for (unsigned i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
RCC_ClockCmd(timerRCC(timerHardware[i].tim), ENABLE);
}
#if defined(STM32F3) || defined(STM32F4)
for (int timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
for (unsigned timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
if (timerHardwarePtr->usageFlags == TIM_USE_NONE) {
continue;
@ -795,10 +795,11 @@ void timerInit(void)
#endif
// initialize timer channel structures
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
for (unsigned i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
timerChannelInfo[i].type = TYPE_FREE;
}
for (int i = 0; i < USED_TIMER_COUNT; i++) {
for (unsigned i = 0; i < USED_TIMER_COUNT; i++) {
timerInfo[i].priority = ~0;
}
}
@ -852,22 +853,6 @@ void timerForceOverflow(TIM_TypeDef *tim)
}
}
const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag)
{
if (!tag) {
return NULL;
}
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
if (timerHardware[i].tag == tag) {
if (timerHardware[i].usageFlags & flag || flag == 0) {
return &timerHardware[i];
}
}
}
return NULL;
}
#if !defined(USE_HAL_DRIVER)
void timerOCInit(TIM_TypeDef *tim, uint8_t channel, TIM_OCInitTypeDef *init)
{
@ -935,7 +920,7 @@ uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz)
uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hz)
{
return ((uint16_t)((timerClock(tim) / (prescaler + 1)) / hz));
return (uint16_t)((timerClock(tim) / (prescaler + 1)) / hz);
}
uint16_t timerGetPrescalerByDesiredHertz(TIM_TypeDef *tim, uint32_t hz)

View File

@ -25,6 +25,11 @@
#include "drivers/io_types.h"
#include "rcc_types.h"
#include "drivers/timer_def.h"
#define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4
#define CC_INDEX_FROM_CHANNEL(x) ((uint8_t)((x) >> 2))
#define CC_CHANNEL_FROM_INDEX(x) ((uint16_t)(x) << 2)
typedef uint16_t captureCompare_t; // 16 bit on both 103 and 303, just register access must be 32bit sometimes (use timCCR_t)
@ -199,7 +204,8 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint32_t hz); // TODO -
rccPeriphTag_t timerRCC(TIM_TypeDef *tim);
uint8_t timerInputIrq(TIM_TypeDef *tim);
const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag);
const timerHardware_t *timerGetByTag(ioTag_t ioTag);
ioTag_t timerioTagGetByUsage(timerUsageFlag_e usageFlag, uint8_t index);
#if defined(USE_HAL_DRIVER)
TIM_HandleTypeDef* timerFindTimerHandle(TIM_TypeDef *tim);

View File

@ -0,0 +1,73 @@
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software under the terms of the
* GNU General Public License as published by the Free Software
* Foundation, either version 3 of the License, or (at your option)
* any later version.
*
* Cleanflight and Betaflight are distributed in the hope that they
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include "drivers/io.h"
#include "timer.h"
#ifdef USE_TIMER_MGMT
#include "pg/timerio.h"
#endif
uint8_t timerIndexByTag(ioTag_t ioTag)
{
#ifdef USE_TIMER_MGMT
for (unsigned i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
if (timerIOConfig(i)->ioTag == ioTag) {
return timerIOConfig(i)->index;
}
}
#else
UNUSED(ioTag);
#endif
return 0;
}
const timerHardware_t *timerGetByTag(ioTag_t ioTag)
{
if (!ioTag) {
return NULL;
}
uint8_t timerIndex = timerIndexByTag(ioTag);
uint8_t index = 1;
for (int i = 0; i < (int)USABLE_TIMER_CHANNEL_COUNT; i++) {
if (timerHardware[i].tag == ioTag) {
if (index == timerIndex || timerIndex == 0) {
return &timerHardware[i];
}
index++;
}
}
return NULL;
}
ioTag_t timerioTagGetByUsage(timerUsageFlag_e usageFlag, uint8_t index)
{
uint8_t currentIndex = 0;
for (int i = 0; i < (int)USABLE_TIMER_CHANNEL_COUNT; i++) {
if ((timerHardware[i].usageFlags & usageFlag) == usageFlag) {
if (currentIndex == index) {
return timerHardware[i].tag;
}
currentIndex++;
}
}
return IO_TAG_NONE;
}

View File

@ -32,6 +32,8 @@
#include "drivers/nvic.h"
#include "drivers/io.h"
#include "drivers/dma.h"
#include "rcc.h"
#include "timer.h"
@ -49,7 +51,6 @@
/// TODO: HAL in a lot af calls lookupTimerIndex is used. Instead of passing the timer instance the index should be passed.
#define USED_TIMER_COUNT BITCOUNT(USED_TIMERS)
#define CC_CHANNELS_PER_TIMER 4 // TIM_Channel_1..4
#define TIM_IT_CCx(ch) (TIM_IT_CC1 << ((ch) / 4))
@ -872,7 +873,7 @@ void timerInit(void)
}
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
for (int timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
for (unsigned timerIndex = 0; timerIndex < USABLE_TIMER_CHANNEL_COUNT; timerIndex++) {
const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
if (timerHardwarePtr->usageFlags == TIM_USE_NONE) {
continue;
@ -882,11 +883,17 @@ void timerInit(void)
}
#endif
/* enable the timer peripherals */
for (unsigned i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
RCC_ClockCmd(timerRCC(timerHardware[i].tim), ENABLE);
}
// initialize timer channel structures
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
for (unsigned i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
timerChannelInfo[i].type = TYPE_FREE;
}
for (int i = 0; i < USED_TIMER_COUNT; i++) {
for (unsigned i = 0; i < USED_TIMER_COUNT; i++) {
timerInfo[i].priority = ~0;
}
}
@ -941,18 +948,6 @@ void timerForceOverflow(TIM_TypeDef *tim)
}
}
const timerHardware_t *timerGetByTag(ioTag_t tag, timerUsageFlag_e flag)
{
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
if (timerHardware[i].tag == tag) {
if (timerHardware[i].usageFlags & flag || flag == 0) {
return &timerHardware[i];
}
}
}
return NULL;
}
// DMA_Handle_index
uint16_t timerDmaIndex(uint8_t channel)
{
@ -992,7 +987,7 @@ uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz)
uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hz)
{
return ((uint16_t)((timerClock(tim) / (prescaler + 1)) / hz));
return (uint16_t)((timerClock(tim) / (prescaler + 1)) / hz);
}
uint16_t timerGetPrescalerByDesiredHertz(TIM_TypeDef *tim, uint32_t hz)

View File

@ -64,7 +64,7 @@ void transponderIrHardwareInit(ioTag_t ioTag, transponder_t *transponder)
return;
}
const timerHardware_t *timerHardware = timerGetByTag(ioTag, TIM_USE_ANY);
const timerHardware_t *timerHardware = timerGetByTag(ioTag);
TIM_TypeDef *timer = timerHardware->tim;
timerChannel = timerHardware->channel;

View File

@ -72,7 +72,7 @@ void transponderIrHardwareInit(ioTag_t ioTag, transponder_t *transponder)
TIM_OCInitTypeDef TIM_OCInitStructure;
DMA_InitTypeDef DMA_InitStructure;
const timerHardware_t *timerHardware = timerGetByTag(ioTag, TIM_USE_ANY);
const timerHardware_t *timerHardware = timerGetByTag(ioTag);
timer = timerHardware->tim;
if (timerHardware->dmaRef == NULL) {

View File

@ -359,7 +359,7 @@ static void validateAndFixConfig(void)
#endif
#if defined(USE_BEEPER)
if (beeperDevConfig()->frequency && !timerGetByTag(beeperDevConfig()->ioTag, TIM_USE_BEEPER)) {
if (beeperDevConfig()->frequency && !timerGetByTag(beeperDevConfig()->ioTag)) {
beeperDevConfigMutable()->frequency = 0;
}
#endif

View File

@ -39,6 +39,7 @@
#include "drivers/pwm_output.h"
#include "drivers/pwm_esc_detect.h"
#include "drivers/time.h"
#include "drivers/io.h"
#include "io/motors.h"
@ -103,12 +104,8 @@ void pgResetFn_motorConfig(motorConfig_t *motorConfig)
motorConfig->dev.useBurstDshot = ENABLE_DSHOT_DMAR;
#endif
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->dev.ioTags[motorIndex] = timerHardware[i].tag;
motorIndex++;
}
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS; motorIndex++) {
motorConfig->dev.ioTags[motorIndex] = timerioTagGetByUsage(TIM_USE_MOTOR, motorIndex);
}
motorConfig->motorPoleCount = 14; // Most brushes motors that we use are 14 poles

View File

@ -66,12 +66,8 @@ void pgResetFn_servoConfig(servoConfig_t *servoConfig)
servoConfig->servo_lowpass_freq = 0;
servoConfig->channelForwardingStartChannel = AUX1;
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->dev.ioTags[servoIndex] = timerHardware[i].tag;
servoIndex++;
}
for (unsigned servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
servoConfig->dev.ioTags[servoIndex] = timerioTagGetByUsage(TIM_USE_SERVO, servoIndex);
}
}

View File

@ -174,13 +174,9 @@ void pgResetFn_ledStripConfig(ledStripConfig_t *ledStripConfig)
ledStripConfig->ledstrip_visual_beeper = 0;
ledStripConfig->ledstrip_aux_channel = THROTTLE;
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
if (timerHardware[i].usageFlags & TIM_USE_LED) {
ledStripConfig->ioTag = timerHardware[i].tag;
return;
}
}
ledStripConfig->ioTag = IO_TAG_NONE;
#ifndef UNIT_TEST
ledStripConfig->ioTag = timerioTagGetByUsage(TIM_USE_LED, 0);
#endif
}
static int scaledThrottle;

View File

@ -38,12 +38,8 @@ PG_REGISTER_WITH_RESET_FN(pwmConfig_t, pwmConfig, PG_PWM_CONFIG, 0);
void pgResetFn_pwmConfig(pwmConfig_t *pwmConfig)
{
pwmConfig->inputFilteringMode = INPUT_FILTERING_DISABLED;
int inputIndex = 0;
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && inputIndex < PWM_INPUT_PORT_COUNT; i++) {
if (timerHardware[i].usageFlags & TIM_USE_PWM) {
pwmConfig->ioTags[inputIndex] = timerHardware[i].tag;
inputIndex++;
}
for (unsigned inputIndex = 0; inputIndex < PWM_INPUT_PORT_COUNT; inputIndex++) {
pwmConfig->ioTags[inputIndex] = timerioTagGetByUsage(TIM_USE_PWM, inputIndex);
}
}
#endif
@ -56,14 +52,7 @@ void pgResetFn_ppmConfig(ppmConfig_t *ppmConfig)
#ifdef PPM_PIN
ppmConfig->ioTag = IO_TAG(PPM_PIN);
#else
for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
if (timerHardware[i].usageFlags & TIM_USE_PPM) {
ppmConfig->ioTag = timerHardware[i].tag;
return;
}
}
ppmConfig->ioTag = IO_TAG_NONE;
ppmConfig->ioTag = timerioTagGetByUsage(TIM_USE_PPM, 0);
#endif
}
#endif