mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-14 03:50:02 +03:00
Added resource index display.
This commit is contained in:
parent
c2db38fec9
commit
768b345166
20 changed files with 74 additions and 80 deletions
|
@ -61,6 +61,7 @@ uint8_t cliMode = 0;
|
|||
#include "drivers/adc.h"
|
||||
#include "drivers/buf_writer.h"
|
||||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/dma.h"
|
||||
#include "drivers/dma_reqmap.h"
|
||||
#include "drivers/camera_control.h"
|
||||
#include "drivers/compass/compass.h"
|
||||
|
@ -76,6 +77,7 @@ uint8_t cliMode = 0;
|
|||
#include "drivers/dshot_dpwm.h"
|
||||
#include "drivers/dshot_command.h"
|
||||
#include "drivers/rangefinder/rangefinder_hcsr04.h"
|
||||
#include "drivers/resource.h"
|
||||
#include "drivers/sdcard.h"
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/serial.h"
|
||||
|
@ -4903,15 +4905,13 @@ static void showDma(void)
|
|||
cliRepeat('-', 20);
|
||||
#endif
|
||||
for (int i = 1; i <= DMA_LAST_HANDLER; i++) {
|
||||
const char* owner;
|
||||
owner = ownerNames[dmaGetOwner(i)];
|
||||
const resourceOwner_t *owner = dmaGetOwner(i);
|
||||
|
||||
cliPrintf(DMA_OUTPUT_STRING, DMA_DEVICE_NO(i), DMA_DEVICE_INDEX(i));
|
||||
uint8_t resourceIndex = dmaGetResourceIndex(i);
|
||||
if (resourceIndex > 0) {
|
||||
cliPrintLinef(" %s %d", owner, resourceIndex);
|
||||
if (owner->resourceIndex > 0) {
|
||||
cliPrintLinef(" %s %d", ownerNames[owner->owner], owner->resourceIndex);
|
||||
} else {
|
||||
cliPrintLinef(" %s", owner);
|
||||
cliPrintLinef(" %s", ownerNames[owner->owner]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -5436,15 +5436,19 @@ static void showTimers(void)
|
|||
cliPrintf("TIM%d:", timerNumber);
|
||||
bool timerUsed = false;
|
||||
for (unsigned timerIndex = 0; timerIndex < CC_CHANNELS_PER_TIMER; timerIndex++) {
|
||||
const resourceOwner_e owner = timerGetOwner(timerNumber, CC_CHANNEL_FROM_INDEX(timerIndex));
|
||||
if (owner) {
|
||||
const resourceOwner_t *timerOwner = timerGetOwner(timerNumber, CC_CHANNEL_FROM_INDEX(timerIndex));
|
||||
if (timerOwner->owner) {
|
||||
if (!timerUsed) {
|
||||
timerUsed = true;
|
||||
|
||||
cliPrintLinefeed();
|
||||
}
|
||||
|
||||
cliPrintLinef(" CH%d: %s", timerIndex + 1, ownerNames[owner]);
|
||||
if (timerOwner->resourceIndex > 0) {
|
||||
cliPrintLinef(" CH%d: %s %d", timerIndex + 1, ownerNames[timerOwner->owner], timerOwner->resourceIndex);
|
||||
} else {
|
||||
cliPrintLinef(" CH%d: %s", timerIndex + 1, ownerNames[timerOwner->owner]);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -131,7 +131,7 @@ void cameraControlInit(void)
|
|||
|
||||
if (CAMERA_CONTROL_MODE_HARDWARE_PWM == cameraControlConfig()->mode) {
|
||||
#ifdef CAMERA_CONTROL_HARDWARE_PWM_AVAILABLE
|
||||
const timerHardware_t *timerHardware = timerAllocate(cameraControlConfig()->ioTag, OWNER_CAMERA_CONTROL);
|
||||
const timerHardware_t *timerHardware = timerAllocate(cameraControlConfig()->ioTag, OWNER_CAMERA_CONTROL, 0);
|
||||
|
||||
if (!timerHardware) {
|
||||
return;
|
||||
|
|
|
@ -93,8 +93,8 @@ void dmaInit(dmaIdentifier_e identifier, resourceOwner_e owner, uint8_t resource
|
|||
const int index = DMA_IDENTIFIER_TO_INDEX(identifier);
|
||||
|
||||
RCC_AHBPeriphClockCmd(DMA_RCC(dmaDescriptors[index].dma), ENABLE);
|
||||
dmaDescriptors[index].owner = owner;
|
||||
dmaDescriptors[index].resourceIndex = resourceIndex;
|
||||
dmaDescriptors[index].owner.owner = owner;
|
||||
dmaDescriptors[index].owner.resourceIndex = resourceIndex;
|
||||
}
|
||||
|
||||
void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam)
|
||||
|
@ -115,14 +115,9 @@ void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callbac
|
|||
NVIC_Init(&NVIC_InitStructure);
|
||||
}
|
||||
|
||||
resourceOwner_e dmaGetOwner(dmaIdentifier_e identifier)
|
||||
const resourceOwner_t *dmaGetOwner(dmaIdentifier_e identifier)
|
||||
{
|
||||
return dmaDescriptors[DMA_IDENTIFIER_TO_INDEX(identifier)].owner;
|
||||
}
|
||||
|
||||
uint8_t dmaGetResourceIndex(dmaIdentifier_e identifier)
|
||||
{
|
||||
return dmaDescriptors[DMA_IDENTIFIER_TO_INDEX(identifier)].resourceIndex;
|
||||
return &dmaDescriptors[DMA_IDENTIFIER_TO_INDEX(identifier)].owner;
|
||||
}
|
||||
|
||||
dmaIdentifier_e dmaGetIdentifier(const dmaResource_t* channel)
|
||||
|
|
|
@ -20,7 +20,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#include "resource.h"
|
||||
#include "drivers/resource.h"
|
||||
|
||||
// dmaResource_t is a opaque data type which represents a single DMA engine,
|
||||
// called and implemented differently in different families of STM32s.
|
||||
|
@ -52,7 +52,7 @@ typedef struct dmaChannelDescriptor_s {
|
|||
uint8_t flagsShift;
|
||||
IRQn_Type irqN;
|
||||
uint32_t userParam;
|
||||
resourceOwner_e owner;
|
||||
resourceOwner_t owner;
|
||||
uint8_t resourceIndex;
|
||||
uint32_t completeFlag;
|
||||
} dmaChannelDescriptor_t;
|
||||
|
@ -102,8 +102,8 @@ typedef enum {
|
|||
.flagsShift = f, \
|
||||
.irqN = d ## _Stream ## s ## _IRQn, \
|
||||
.userParam = 0, \
|
||||
.owner = 0, \
|
||||
.resourceIndex = 0 \
|
||||
.owner.owner = 0, \
|
||||
.owner.resourceIndex = 0 \
|
||||
}
|
||||
|
||||
#define DEFINE_DMA_IRQ_HANDLER(d, s, i) void DMA ## d ## _Stream ## s ## _IRQHandler(void) {\
|
||||
|
@ -163,8 +163,8 @@ typedef enum {
|
|||
.flagsShift = f, \
|
||||
.irqN = d ## _Channel ## c ## _IRQn, \
|
||||
.userParam = 0, \
|
||||
.owner = 0, \
|
||||
.resourceIndex = 0 \
|
||||
.owner.owner = 0, \
|
||||
.owner.resourceIndex = 0 \
|
||||
}
|
||||
|
||||
#define DEFINE_DMA_IRQ_HANDLER(d, c, i) void DMA ## d ## _Channel ## c ## _IRQHandler(void) {\
|
||||
|
@ -212,8 +212,7 @@ dmaResource_t* dmaGetRefByIdentifier(const dmaIdentifier_e identifier);
|
|||
void dmaInit(dmaIdentifier_e identifier, resourceOwner_e owner, uint8_t resourceIndex);
|
||||
void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam);
|
||||
|
||||
resourceOwner_e dmaGetOwner(dmaIdentifier_e identifier);
|
||||
uint8_t dmaGetResourceIndex(dmaIdentifier_e identifier);
|
||||
const resourceOwner_t *dmaGetOwner(dmaIdentifier_e identifier);
|
||||
dmaChannelDescriptor_t* dmaGetDescriptorByIdentifier(const dmaIdentifier_e identifier);
|
||||
|
||||
//
|
||||
|
|
|
@ -78,8 +78,8 @@ void dmaInit(dmaIdentifier_e identifier, resourceOwner_e owner, uint8_t resource
|
|||
{
|
||||
const int index = DMA_IDENTIFIER_TO_INDEX(identifier);
|
||||
RCC_AHB1PeriphClockCmd(DMA_RCC(dmaDescriptors[index].dma), ENABLE);
|
||||
dmaDescriptors[index].owner = owner;
|
||||
dmaDescriptors[index].resourceIndex = resourceIndex;
|
||||
dmaDescriptors[index].owner.owner = owner;
|
||||
dmaDescriptors[index].owner.resourceIndex = resourceIndex;
|
||||
}
|
||||
|
||||
#define RETURN_TCIF_FLAG(s, n) if (s == DMA1_Stream ## n || s == DMA2_Stream ## n) return DMA_IT_TCIF ## n
|
||||
|
@ -115,14 +115,9 @@ void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callbac
|
|||
NVIC_Init(&NVIC_InitStructure);
|
||||
}
|
||||
|
||||
resourceOwner_e dmaGetOwner(dmaIdentifier_e identifier)
|
||||
const resourceOwner_t *dmaGetOwner(dmaIdentifier_e identifier)
|
||||
{
|
||||
return dmaDescriptors[DMA_IDENTIFIER_TO_INDEX(identifier)].owner;
|
||||
}
|
||||
|
||||
uint8_t dmaGetResourceIndex(dmaIdentifier_e identifier)
|
||||
{
|
||||
return dmaDescriptors[DMA_IDENTIFIER_TO_INDEX(identifier)].resourceIndex;
|
||||
return &dmaDescriptors[DMA_IDENTIFIER_TO_INDEX(identifier)].owner;
|
||||
}
|
||||
|
||||
dmaIdentifier_e dmaGetIdentifier(const dmaResource_t* instance)
|
||||
|
|
|
@ -91,8 +91,8 @@ void dmaInit(dmaIdentifier_e identifier, resourceOwner_e owner, uint8_t resource
|
|||
const int index = DMA_IDENTIFIER_TO_INDEX(identifier);
|
||||
|
||||
enableDmaClock(index);
|
||||
dmaDescriptors[index].owner = owner;
|
||||
dmaDescriptors[index].resourceIndex = resourceIndex;
|
||||
dmaDescriptors[index].owner.owner = owner;
|
||||
dmaDescriptors[index].owner.resourceIndex = resourceIndex;
|
||||
}
|
||||
|
||||
void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam)
|
||||
|
@ -107,14 +107,9 @@ void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callbac
|
|||
HAL_NVIC_EnableIRQ(dmaDescriptors[index].irqN);
|
||||
}
|
||||
|
||||
resourceOwner_e dmaGetOwner(dmaIdentifier_e identifier)
|
||||
const resourceOwner_t *dmaGetOwner(dmaIdentifier_e identifier)
|
||||
{
|
||||
return dmaDescriptors[DMA_IDENTIFIER_TO_INDEX(identifier)].owner;
|
||||
}
|
||||
|
||||
uint8_t dmaGetResourceIndex(dmaIdentifier_e identifier)
|
||||
{
|
||||
return dmaDescriptors[DMA_IDENTIFIER_TO_INDEX(identifier)].resourceIndex;
|
||||
return &dmaDescriptors[DMA_IDENTIFIER_TO_INDEX(identifier)].owner;
|
||||
}
|
||||
|
||||
dmaIdentifier_e dmaGetIdentifier(const dmaResource_t* stream)
|
||||
|
|
|
@ -95,8 +95,8 @@ void dmaInit(dmaIdentifier_e identifier, resourceOwner_e owner, uint8_t resource
|
|||
const int index = DMA_IDENTIFIER_TO_INDEX(identifier);
|
||||
|
||||
enableDmaClock(index);
|
||||
dmaDescriptors[index].owner = owner;
|
||||
dmaDescriptors[index].resourceIndex = resourceIndex;
|
||||
dmaDescriptors[index].owner.owner = owner;
|
||||
dmaDescriptors[index].owner.resourceIndex = resourceIndex;
|
||||
}
|
||||
|
||||
void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam)
|
||||
|
@ -111,14 +111,9 @@ void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callbac
|
|||
HAL_NVIC_EnableIRQ(dmaDescriptors[index].irqN);
|
||||
}
|
||||
|
||||
resourceOwner_e dmaGetOwner(dmaIdentifier_e identifier)
|
||||
const resourceOwner_t *dmaGetOwner(dmaIdentifier_e identifier)
|
||||
{
|
||||
return dmaDescriptors[DMA_IDENTIFIER_TO_INDEX(identifier)].owner;
|
||||
}
|
||||
|
||||
uint8_t dmaGetResourceIndex(dmaIdentifier_e identifier)
|
||||
{
|
||||
return dmaDescriptors[DMA_IDENTIFIER_TO_INDEX(identifier)].resourceIndex;
|
||||
return &dmaDescriptors[DMA_IDENTIFIER_TO_INDEX(identifier)].owner;
|
||||
}
|
||||
|
||||
dmaIdentifier_e dmaGetIdentifier(const dmaResource_t* stream)
|
||||
|
|
|
@ -177,7 +177,7 @@ motorDevice_t *dshotPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t idl
|
|||
|
||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
||||
const ioTag_t tag = motorConfig->ioTags[motorIndex];
|
||||
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR);
|
||||
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||
|
||||
if (timerHardware == NULL) {
|
||||
/* not enough motors initialised for the mixer or a break in the motors */
|
||||
|
|
|
@ -55,7 +55,7 @@ bool ws2811LedStripHardwareInit(ioTag_t ioTag)
|
|||
return false;
|
||||
}
|
||||
|
||||
const timerHardware_t *timerHardware = timerAllocate(ioTag, OWNER_LED_STRIP);
|
||||
const timerHardware_t *timerHardware = timerAllocate(ioTag, OWNER_LED_STRIP, 0);
|
||||
|
||||
if (timerHardware == NULL) {
|
||||
return false;
|
||||
|
|
|
@ -83,7 +83,7 @@ bool ws2811LedStripHardwareInit(ioTag_t ioTag)
|
|||
TIM_OCInitTypeDef TIM_OCInitStructure;
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
|
||||
const timerHardware_t *timerHardware = timerAllocate(ioTag, OWNER_LED_STRIP);
|
||||
const timerHardware_t *timerHardware = timerAllocate(ioTag, OWNER_LED_STRIP, 0);
|
||||
|
||||
if (timerHardware == NULL) {
|
||||
return false;
|
||||
|
|
|
@ -213,7 +213,7 @@ motorDevice_t *motorPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t idl
|
|||
|
||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) {
|
||||
const ioTag_t tag = motorConfig->ioTags[motorIndex];
|
||||
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR);
|
||||
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||
|
||||
if (timerHardware == NULL) {
|
||||
/* not enough motors initialised for the mixer or a break in the motors */
|
||||
|
@ -294,7 +294,7 @@ void servoDevInit(const servoDevConfig_t *servoConfig)
|
|||
|
||||
IOInit(servos[servoIndex].io, OWNER_SERVO, RESOURCE_INDEX(servoIndex));
|
||||
|
||||
const timerHardware_t *timer = timerAllocate(tag, OWNER_SERVO);
|
||||
const timerHardware_t *timer = timerAllocate(tag, OWNER_SERVO, RESOURCE_INDEX(servoIndex));
|
||||
|
||||
if (timer == NULL) {
|
||||
/* flag failure and disable ability to arm */
|
||||
|
|
|
@ -100,6 +100,11 @@ typedef enum {
|
|||
OWNER_TOTAL_COUNT
|
||||
} resourceOwner_e;
|
||||
|
||||
typedef struct resourceOwner_s {
|
||||
resourceOwner_e owner;
|
||||
uint8_t resourceIndex;
|
||||
} resourceOwner_t;
|
||||
|
||||
extern const char * const ownerNames[OWNER_TOTAL_COUNT];
|
||||
|
||||
#define RESOURCE_INDEX(x) (x + 1)
|
||||
|
|
|
@ -371,7 +371,7 @@ void pwmRxInit(const pwmConfig_t *pwmConfig)
|
|||
|
||||
pwmInputPort_t *port = &pwmInputPorts[channel];
|
||||
|
||||
const timerHardware_t *timer = timerAllocate(pwmConfig->ioTags[channel], OWNER_PWMINPUT);
|
||||
const timerHardware_t *timer = timerAllocate(pwmConfig->ioTags[channel], OWNER_PWMINPUT, RESOURCE_INDEX(channel));
|
||||
|
||||
if (!timer) {
|
||||
/* TODO: maybe fail here if not enough channels? */
|
||||
|
@ -428,7 +428,7 @@ void ppmRxInit(const ppmConfig_t *ppmConfig)
|
|||
|
||||
pwmInputPort_t *port = &pwmInputPorts[FIRST_PWM_PORT];
|
||||
|
||||
const timerHardware_t *timer = timerAllocate(ppmConfig->ioTag, OWNER_PPMINPUT);
|
||||
const timerHardware_t *timer = timerAllocate(ppmConfig->ioTag, OWNER_PPMINPUT, 0);
|
||||
if (!timer) {
|
||||
/* TODO: fail here? */
|
||||
return;
|
||||
|
|
|
@ -668,7 +668,7 @@ static serialPort_t *openEscSerial(const motorDevConfig_t *motorConfig, escSeria
|
|||
}
|
||||
if (mode != PROTOCOL_KISSALL) {
|
||||
const ioTag_t tag = motorConfig->ioTags[output];
|
||||
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR);
|
||||
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, 0);
|
||||
|
||||
if (timerHardware == NULL) {
|
||||
return NULL;
|
||||
|
@ -686,7 +686,7 @@ static serialPort_t *openEscSerial(const motorDevConfig_t *motorConfig, escSeria
|
|||
}
|
||||
|
||||
escSerial->mode = mode;
|
||||
escSerial->txTimerHardware = timerAllocate(escSerialConfig()->ioTag, OWNER_MOTOR);
|
||||
escSerial->txTimerHardware = timerAllocate(escSerialConfig()->ioTag, OWNER_MOTOR, 0);
|
||||
if (escSerial->txTimerHardware == NULL) {
|
||||
return NULL;
|
||||
}
|
||||
|
@ -745,7 +745,7 @@ static serialPort_t *openEscSerial(const motorDevConfig_t *motorConfig, escSeria
|
|||
if (pwmMotors[i].enabled && pwmMotors[i].io != IO_NONE) {
|
||||
const ioTag_t tag = motorConfig->ioTags[i];
|
||||
if (tag != IO_TAG_NONE) {
|
||||
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR);
|
||||
const timerHardware_t *timerHardware = timerAllocate(tag, OWNER_MOTOR, 0);
|
||||
if (timerHardware) {
|
||||
escSerialOutputPortConfig(timerHardware);
|
||||
escOutputs[escSerial->outputCount].io = pwmMotors[i].io;
|
||||
|
|
|
@ -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 = timerAllocate(tagRx, OWNER_SERIAL_RX);
|
||||
const timerHardware_t *timerTx = timerAllocate(tagTx, OWNER_SERIAL_TX);
|
||||
const timerHardware_t *timerRx = timerAllocate(tagRx, OWNER_SERIAL_RX, RESOURCE_INDEX(portIndex + RESOURCE_SOFT_OFFSET));
|
||||
const timerHardware_t *timerTx = timerAllocate(tagTx, OWNER_SERIAL_TX, RESOURCE_INDEX(portIndex + RESOURCE_SOFT_OFFSET));
|
||||
|
||||
IO_t rxIO = IOGetByTag(tagRx);
|
||||
IO_t txIO = IOGetByTag(tagTx);
|
||||
|
|
|
@ -61,12 +61,12 @@ static void pwmToggleBeeper(void)
|
|||
|
||||
static void beeperPwmInit(const ioTag_t tag, uint16_t frequency)
|
||||
{
|
||||
const timerHardware_t *timer = timerAllocate(tag, OWNER_BEEPER);
|
||||
const timerHardware_t *timer = timerAllocate(tag, OWNER_BEEPER, 0);
|
||||
IO_t beeperIO = IOGetByTag(tag);
|
||||
|
||||
if (beeperIO && timer) {
|
||||
beeperPwm.io = beeperIO;
|
||||
IOInit(beeperPwm.io, OWNER_BEEPER, RESOURCE_INDEX(0));
|
||||
IOInit(beeperPwm.io, OWNER_BEEPER, 0);
|
||||
#if defined(STM32F1)
|
||||
IOConfigGPIO(beeperPwm.io, IOCFG_AF_PP);
|
||||
#else
|
||||
|
|
|
@ -26,6 +26,7 @@
|
|||
#include "drivers/dma.h"
|
||||
#include "drivers/io_types.h"
|
||||
#include "drivers/rcc_types.h"
|
||||
#include "drivers/resource.h"
|
||||
#include "drivers/timer_def.h"
|
||||
|
||||
#include "pg/timerio.h"
|
||||
|
@ -270,10 +271,10 @@ uint8_t timerInputIrq(TIM_TypeDef *tim);
|
|||
|
||||
#if defined(USE_TIMER_MGMT)
|
||||
timerIOConfig_t *timerIoConfigByTag(ioTag_t ioTag);
|
||||
resourceOwner_e timerGetOwner(int8_t timerNumber, uint16_t timerChannel);
|
||||
const resourceOwner_t *timerGetOwner(int8_t timerNumber, uint16_t timerChannel);
|
||||
#endif
|
||||
const timerHardware_t *timerGetByTag(ioTag_t ioTag);
|
||||
const timerHardware_t *timerAllocate(ioTag_t ioTag, resourceOwner_e owner);
|
||||
const timerHardware_t *timerAllocate(ioTag_t ioTag, resourceOwner_e owner, uint8_t resourceIndex);
|
||||
const timerHardware_t *timerGetByTagAndIndex(ioTag_t ioTag, unsigned timerIndex);
|
||||
ioTag_t timerioTagGetByUsage(timerUsageFlag_e usageFlag, uint8_t index);
|
||||
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
#ifdef USE_TIMER_MGMT
|
||||
#include "pg/timerio.h"
|
||||
|
||||
static resourceOwner_e timerOwners[MAX_TIMER_PINMAP_COUNT];
|
||||
static resourceOwner_t timerOwners[MAX_TIMER_PINMAP_COUNT];
|
||||
|
||||
timerIOConfig_t *timerIoConfigByTag(ioTag_t ioTag)
|
||||
{
|
||||
|
@ -78,19 +78,21 @@ const timerHardware_t *timerGetByTag(ioTag_t ioTag)
|
|||
return timerGetByTagAndIndex(ioTag, timerIndex);
|
||||
}
|
||||
|
||||
resourceOwner_e timerGetOwner(int8_t timerNumber, uint16_t timerChannel)
|
||||
const resourceOwner_t *timerGetOwner(int8_t timerNumber, uint16_t timerChannel)
|
||||
{
|
||||
static resourceOwner_t freeOwner = { .owner = OWNER_FREE, .resourceIndex = 0 };
|
||||
|
||||
for (unsigned i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
|
||||
const timerHardware_t *timer = timerGetByTagAndIndex(timerIOConfig(i)->ioTag, timerIOConfig(i)->index);
|
||||
if (timer && timerGetTIMNumber(timer->tim) == timerNumber && timer->channel == timerChannel) {
|
||||
return timerOwners[i];
|
||||
return &timerOwners[i];
|
||||
}
|
||||
}
|
||||
|
||||
return OWNER_FREE;
|
||||
return &freeOwner;
|
||||
}
|
||||
|
||||
const timerHardware_t *timerAllocate(ioTag_t ioTag, resourceOwner_e owner)
|
||||
const timerHardware_t *timerAllocate(ioTag_t ioTag, resourceOwner_e owner, uint8_t resourceIndex)
|
||||
{
|
||||
if (!ioTag) {
|
||||
return NULL;
|
||||
|
@ -100,11 +102,12 @@ const timerHardware_t *timerAllocate(ioTag_t ioTag, resourceOwner_e owner)
|
|||
if (timerIOConfig(i)->ioTag == ioTag) {
|
||||
const timerHardware_t *timer = timerGetByTagAndIndex(ioTag, timerIOConfig(i)->index);
|
||||
|
||||
if (timerGetOwner(timerGetTIMNumber(timer->tim), timer->channel)) {
|
||||
if (timerGetOwner(timerGetTIMNumber(timer->tim), timer->channel)->owner) {
|
||||
return NULL;
|
||||
}
|
||||
|
||||
timerOwners[i] = owner;
|
||||
timerOwners[i].owner = owner;
|
||||
timerOwners[i].resourceIndex = resourceIndex;
|
||||
|
||||
return timer;
|
||||
}
|
||||
|
@ -128,9 +131,10 @@ const timerHardware_t *timerGetByTag(ioTag_t ioTag)
|
|||
return NULL;
|
||||
}
|
||||
|
||||
const timerHardware_t *timerAllocate(ioTag_t ioTag, resourceOwner_e owner)
|
||||
const timerHardware_t *timerAllocate(ioTag_t ioTag, resourceOwner_e owner, uint8_t resourceIndex)
|
||||
{
|
||||
UNUSED(owner);
|
||||
UNUSED(resourceIndex);
|
||||
|
||||
return timerGetByTag(ioTag);
|
||||
}
|
||||
|
@ -155,3 +159,4 @@ ioTag_t timerioTagGetByUsage(timerUsageFlag_e usageFlag, uint8_t index)
|
|||
return IO_TAG_NONE;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -72,7 +72,7 @@ void transponderIrHardwareInit(ioTag_t ioTag, transponder_t *transponder)
|
|||
return;
|
||||
}
|
||||
|
||||
const timerHardware_t *timerHardware = timerAllocate(ioTag, OWNER_TRANSPONDER);
|
||||
const timerHardware_t *timerHardware = timerAllocate(ioTag, OWNER_TRANSPONDER, 0);
|
||||
TIM_TypeDef *timer = timerHardware->tim;
|
||||
timerChannel = timerHardware->channel;
|
||||
output = timerHardware->output;
|
||||
|
|
|
@ -67,7 +67,7 @@ void transponderIrHardwareInit(ioTag_t ioTag, transponder_t *transponder)
|
|||
TIM_OCInitTypeDef TIM_OCInitStructure;
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
|
||||
const timerHardware_t *timerHardware = timerAllocate(ioTag, OWNER_TRANSPONDER);
|
||||
const timerHardware_t *timerHardware = timerAllocate(ioTag, OWNER_TRANSPONDER, 0);
|
||||
timer = timerHardware->tim;
|
||||
alternateFunction = timerHardware->alternateFunction;
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue