[BSP Driver]: Fix compile errors&cleanup (#26)

* FIX at32 driver warnings

* fix at32 glue driver warnings
This commit is contained in:
EMSR 2023-02-04 13:04:55 +08:00 committed by GitHub
parent 3962c92dba
commit 410007c69b
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
13 changed files with 46 additions and 147 deletions

View File

@ -167,6 +167,7 @@ flag_status qspi_flag_get(qspi_type* qspi_x, uint32_t flag)
*/
void qspi_flag_clear(qspi_type* qspi_x, uint32_t flag)
{
UNUSED(flag);
qspi_x->cmdsts = QSPI_CMDSTS_FLAG;
}

View File

@ -444,6 +444,7 @@ void usb_write_packet(otg_global_type *usbx, uint8_t *pusr_buf, uint16_t num, ui
*/
void usb_read_packet(otg_global_type *usbx, uint8_t *pusr_buf, uint16_t num, uint16_t nbytes)
{
UNUSED(num);
uint32_t n_index;
uint32_t nhbytes = (nbytes + 3) / 4;
uint32_t *pbuf = (uint32_t *)pusr_buf;

View File

@ -137,6 +137,7 @@ void usbd_core_out_handler(usbd_core_type *udev, uint8_t ept_addr)
*/
void usbd_core_setup_handler(usbd_core_type *udev, uint8_t ept_num)
{
UNUSED(ept_num);
/* setup parse */
usbd_setup_request_parse(&udev->setup, udev->setup_buffer);
@ -742,6 +743,7 @@ usb_sts_type usbd_core_init(usbd_core_type *udev,
usbd_desc_handler *desc_handler,
uint8_t core_id)
{
UNUSED(core_id);
usb_reg_type *usbx;
otg_device_type *dev;
otg_eptin_type *ept_in;

View File

@ -61,6 +61,15 @@ linecoding_type linecoding =
0,
8
};
/** function pointers used in vTable
* @}
*/
static void (*ctrlLineStateCb)(void *context, uint16_t ctrlLineState);
static void *ctrlLineStateCbContext;
static void (*baudRateCb)(void *context, uint32_t baud);
static void *baudRateCbContext;
/* cdc data struct */
cdc_struct_type cdc_struct;
@ -205,6 +214,7 @@ static usb_sts_type class_ept0_tx_handler(void *udev)
usb_sts_type status = USB_OK;
/* ...user code... */
UNUSED(udev);
return status;
}
@ -289,6 +299,7 @@ static usb_sts_type class_sof_handler(void *udev)
usb_sts_type status = USB_OK;
/* ...user code... */
UNUSED(udev);
return status;
}
@ -301,6 +312,7 @@ static usb_sts_type class_sof_handler(void *udev)
*/
static usb_sts_type class_event_handler(void *udev, usbd_event_type event)
{
UNUSED(udev);
usb_sts_type status = USB_OK;
switch(event)
{
@ -409,6 +421,7 @@ error_status usb_vcp_send_data(void *udev, uint8_t *send_data, uint16_t len)
*/
static void usb_vcp_cmd_process(void *udev, uint8_t cmd, uint8_t *buff, uint16_t len)
{
UNUSED(len);
usbd_core_type *pudev = (usbd_core_type *)udev;
cdc_struct_type *pcdc = (cdc_struct_type *)pudev->class_handler->pdata;
switch(cmd)

View File

@ -84,14 +84,6 @@ typedef struct
}cdc_struct_type;
/**
* @}
*/
static void (*ctrlLineStateCb)(void *context, uint16_t ctrlLineState);
static void *ctrlLineStateCbContext;
static void (*baudRateCb)(void *context, uint32_t baud);
static void *baudRateCbContext;
/** @defgroup USB_cdc_class_exported_functions
* @{

View File

@ -146,6 +146,7 @@ void bot_scsi_reset(void *udev)
*/
void bot_scsi_datain_handler(void *udev, uint8_t ept_num)
{
UNUSED(ept_num);
usbd_core_type *pudev = (usbd_core_type *)udev;
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;
switch(pmsc->msc_state)
@ -175,6 +176,7 @@ void bot_scsi_datain_handler(void *udev, uint8_t ept_num)
*/
void bot_scsi_dataout_handler(void *udev, uint8_t ept_num)
{
UNUSED(ept_num);
usbd_core_type *pudev = (usbd_core_type *)udev;
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;
switch(pmsc->msc_state)
@ -291,6 +293,7 @@ void bot_scsi_send_csw(void *udev, uint8_t status)
*/
void bot_scsi_sense_code(void *udev, uint8_t sense_key, uint8_t asc)
{
UNUSED(udev);
sense_data.sense_key = sense_key;
sense_data.asc = asc;
}
@ -349,6 +352,7 @@ void bot_scsi_stall(void *udev)
*/
usb_sts_type bot_scsi_test_unit(void *udev, uint8_t lun)
{
UNUSED(lun);
usb_sts_type status = USB_OK;
usbd_core_type *pudev = (usbd_core_type *)udev;
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;
@ -412,6 +416,7 @@ usb_sts_type bot_scsi_inquiry(void *udev, uint8_t lun)
*/
usb_sts_type bot_scsi_start_stop(void *udev, uint8_t lun)
{
UNUSED(lun);
usbd_core_type *pudev = (usbd_core_type *)udev;
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;
pmsc->data_len = 0;
@ -426,6 +431,7 @@ usb_sts_type bot_scsi_start_stop(void *udev, uint8_t lun)
*/
usb_sts_type bot_scsi_allow_medium_removal(void *udev, uint8_t lun)
{
UNUSED(lun);
usbd_core_type *pudev = (usbd_core_type *)udev;
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;
pmsc->data_len = 0;
@ -440,6 +446,7 @@ usb_sts_type bot_scsi_allow_medium_removal(void *udev, uint8_t lun)
*/
usb_sts_type bot_scsi_mode_sense6(void *udev, uint8_t lun)
{
UNUSED(lun);
uint8_t data_len = 8;
usbd_core_type *pudev = (usbd_core_type *)udev;
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;
@ -460,6 +467,7 @@ usb_sts_type bot_scsi_mode_sense6(void *udev, uint8_t lun)
*/
usb_sts_type bot_scsi_mode_sense10(void *udev, uint8_t lun)
{
UNUSED(lun);
uint8_t data_len = 8;
usbd_core_type *pudev = (usbd_core_type *)udev;
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;
@ -542,6 +550,7 @@ usb_sts_type bot_scsi_format_capacity(void *udev, uint8_t lun)
*/
usb_sts_type bot_scsi_request_sense(void *udev, uint8_t lun)
{
UNUSED(lun);
uint32_t trans_len = 0x12;
usbd_core_type *pudev = (usbd_core_type *)udev;
msc_type *pmsc = (msc_type *)pudev->class_handler->pdata;

View File

@ -188,6 +188,7 @@ static usb_sts_type class_ept0_tx_handler(void *udev)
usb_sts_type status = USB_OK;
/* ...user code... */
UNUSED(udev);
return status;
}
@ -203,6 +204,7 @@ static usb_sts_type class_ept0_rx_handler(void *udev)
usbd_core_type *pudev = (usbd_core_type *)udev;
uint32_t recv_len = usbd_get_recv_len(pudev, 0);
/* ...user code... */
UNUSED(recv_len);
return status;
}
@ -245,6 +247,7 @@ static usb_sts_type class_sof_handler(void *udev)
usb_sts_type status = USB_OK;
/* ...user code... */
UNUSED(udev);
return status;
}
@ -257,6 +260,7 @@ static usb_sts_type class_sof_handler(void *udev)
*/
static usb_sts_type class_event_handler(void *udev, usbd_event_type event)
{
UNUSED(udev);
usb_sts_type status = USB_OK;
switch(event)
{

View File

@ -21,6 +21,7 @@
* INCLUDING BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE, OR NON-INFRINGEMENT.
*
* mod by EMSR(shanggl@wo.cn)
**************************************************************************
*/
@ -103,11 +104,12 @@
* @brief initializes peripherals used by the i2c.
* @param none
* @retval none
* not use in betaflight
*/
__WEAK void i2c_lowlevel_init(i2c_handle_type* hi2c)
{
}
//__WEAK void i2c_lowlevel_init(i2c_handle_type* hi2c)
//{
//
//}
/**
* @brief i2c peripheral initialization.

View File

@ -33,13 +33,13 @@
uint32_t persistentObjectRead(persistentObjectId_e id)
{
uint32_t value = ertc_bpr_data_read(id);
uint32_t value = ertc_bpr_data_read((ertc_dt_type)id);
return value;
}
void persistentObjectWrite(persistentObjectId_e id, uint32_t value)
{
ertc_bpr_data_write(id,value);
ertc_bpr_data_write((ertc_dt_type)id,value);
}
void persistentObjectRTCEnable(void)

View File

@ -416,13 +416,7 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
//set tim pulse =0 , need timer channel
#ifdef USE_DSHOT_TELEMETRY
// TIM_ICStructInit(&motor->icInitStruct);
// motor->icInitStruct.TIM_ICSelection = TIM_ICSelection_DirectTI;
// motor->icInitStruct.TIM_ICPolarity = TIM_ICPolarity_BothEdge;
// motor->icInitStruct.TIM_ICPrescaler = TIM_ICPSC_DIV1;
// motor->icInitStruct.TIM_Channel = timerHardware->channel;
// motor->icInitStruct.TIM_ICFilter = 2;
// tmr_input_default_para_init(&motor->icInitStruct);
motor->icInitStruct.input_mapped_select = TMR_CC_CHANNEL_MAPPED_DIRECT;
motor->icInitStruct.input_polarity_select = TMR_INPUT_BOTH_EDGE;
motor->icInitStruct.input_channel_select = (timerHardware->channel-1)*2;//FIXME: BUGS ON N CHANNEL
@ -457,33 +451,13 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
if (useBurstDshot) {
motor->timer->dmaBurstBuffer = &dshotBurstDmaBuffer[timerIndex][0];
//#if defined(STM32F3)
// DMAINIT.DMA_MemoryBaseAddr = (uint32_t)motor->timer->dmaBurstBuffer;
// DMAINIT.DMA_DIR = DMA_DIR_PeripheralDST;
//#else
// DMAINIT.DMA_Channel = timerHardware->dmaTimUPChannel;
// DMAINIT.DMA_Memory0BaseAddr = (uint32_t)motor->timer->dmaBurstBuffer;
// DMAINIT.DMA_DIR = DMA_DIR_MemoryToPeripheral;
// DMAINIT.DMA_FIFOMode = DMA_FIFOMode_Enable;
// DMAINIT.DMA_FIFOThreshold = DMA_FIFOThreshold_Full;
// DMAINIT.DMA_MemoryBurst = DMA_MemoryBurst_Single;
// DMAINIT.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
//#endif
// DMAINIT.DMA_PeripheralBaseAddr = (uint32_t)&timerHardware->tim->DMAR;
// DMAINIT.DMA_BufferSize = (pwmProtocolType == PWM_TYPE_PROSHOT1000) ? PROSHOT_DMA_BUFFER_SIZE : DSHOT_DMA_BUFFER_SIZE; // XXX
// DMAINIT.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
// DMAINIT.DMA_MemoryInc = DMA_MemoryInc_Enable;
// DMAINIT.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
// DMAINIT.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
// DMAINIT.DMA_Mode = DMA_Mode_Normal;
// DMAINIT.DMA_Priority = DMA_Priority_High;
DMAINIT.memory_base_addr=(uint32_t)motor->timer->dmaBurstBuffer;
DMAINIT.direction = DMA_DIR_MEMORY_TO_PERIPHERAL;
DMAINIT.buffer_size=(pwmProtocolType == PWM_TYPE_PROSHOT1000) ? PROSHOT_DMA_BUFFER_SIZE : DSHOT_DMA_BUFFER_SIZE; // XXX
DMAINIT.peripheral_base_addr=(uint32_t)&timerHardware->tim->dmadt;
DMAINIT.peripheral_inc_enable=FALSE;
DMAINIT.memory_inc_enable=TRUE;
DMAINIT.peripheral_data_width =DMA_MEMORY_DATA_WIDTH_WORD;
DMAINIT.peripheral_data_width =DMA_PERIPHERAL_DATA_WIDTH_WORD;
DMAINIT.memory_data_width=DMA_MEMORY_DATA_WIDTH_WORD;
DMAINIT.loop_mode_enable=FALSE;
DMAINIT.priority=DMA_PRIORITY_HIGH;
@ -493,17 +467,6 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m
{
motor->dmaBuffer = &dshotDmaBuffer[motorIndex][0];
// DMAINIT.DMA_MemoryBaseAddr = (uint32_t)motor->dmaBuffer;
// DMAINIT.DMA_DIR = DMA_DIR_PeripheralDST;
// DMAINIT.DMA_M2M = DMA_M2M_Disable;
// DMAINIT.DMA_PeripheralBaseAddr = (uint32_t)timerChCCR(timerHardware);
// DMAINIT.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
// DMAINIT.DMA_MemoryInc = DMA_MemoryInc_Enable;
// DMAINIT.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
// DMAINIT.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
// DMAINIT.DMA_Mode = DMA_Mode_Normal;
// DMAINIT.DMA_Priority = DMA_Priority_High;
DMAINIT.memory_base_addr= (uint32_t) motor->dmaBuffer;
DMAINIT.direction= DMA_DIR_MEMORY_TO_PERIPHERAL;
DMAINIT.peripheral_base_addr = (uint32_t)timerChCCR(timerHardware);

View File

@ -25,5 +25,3 @@ typedef uint16_t rccPeriphTag_t;
#else
typedef uint8_t rccPeriphTag_t;
#endif
typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;

View File

@ -411,7 +411,7 @@ static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, const tmr_type *tim
*chain = NULL;
}
// enable or disable IRQ
tmr_interrupt_enable((tmr_type *)tim, TMR_OVF_INT, cfg->overflowCallbackActive ? ENABLE : DISABLE);
tmr_interrupt_enable((tmr_type *)tim, TMR_OVF_INT, cfg->overflowCallbackActive ? TRUE : FALSE);
}
// config edge and overflow callback for channel. Try to avoid per-channel overflowCallback, it is a bit expensive
void timerChConfigCallbacks(const timerHardware_t *timHw, timerCCHandlerRec_t *edgeCallback, timerOvrHandlerRec_t *overflowCallback)
@ -422,13 +422,13 @@ void timerChConfigCallbacks(const timerHardware_t *timHw, timerCCHandlerRec_t *e
}
uint8_t channelIndex = lookupChannelIndex(timHw->channel);
if (edgeCallback == NULL) // disable irq before changing callback to NULL
tmr_interrupt_enable(timHw->tim, TIM_IT_CCx(timHw->channel), DISABLE);
tmr_interrupt_enable(timHw->tim, TIM_IT_CCx(timHw->channel), FALSE);
// setup callback info
timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallback;
timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback;
// enable channel IRQ
if (edgeCallback)
tmr_interrupt_enable(timHw->tim, TIM_IT_CCx(timHw->channel), ENABLE);
tmr_interrupt_enable(timHw->tim, TIM_IT_CCx(timHw->channel), TRUE);
timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim);
}
@ -442,49 +442,6 @@ void timerConfigUpdateCallback(const tmr_type *tim, timerOvrHandlerRec_t *update
timerConfig[timerIndex].updateCallback = updateCallback;
timerChConfig_UpdateOverflow(&timerConfig[timerIndex], tim);
}
//FIXME: 20220331 HERE!
// 双定时器的用法应该用不上
// configure callbacks for pair of channels (1+2 or 3+4).
// Hi(2,4) and Lo(1,3) callbacks are specified, it is not important which timHw channel is used.
// This is intended for dual capture mode (each channel handles one transition)
//void timerChConfigCallbacksDual(const timerHardware_t *timHw, timerCCHandlerRec_t *edgeCallbackLo, timerCCHandlerRec_t *edgeCallbackHi, timerOvrHandlerRec_t *overflowCallback)
//{
// uint8_t timerIndex = lookupTimerIndex(timHw->tim);
// if (timerIndex >= USED_TIMER_COUNT) {
// return;
// }
// uint16_t chLo = timHw->channel & ~TIM_Channel_2; // lower channel
// uint16_t chHi = timHw->channel | TIM_Channel_2; // upper channel
// uint8_t channelIndex = lookupChannelIndex(chLo); // get index of lower channel
//
// if (edgeCallbackLo == NULL) // disable irq before changing setting callback to NULL
// TIM_ITConfig(timHw->tim, TIM_IT_CCx(chLo), DISABLE);
// if (edgeCallbackHi == NULL) // disable irq before changing setting callback to NULL
// TIM_ITConfig(timHw->tim, TIM_IT_CCx(chHi), DISABLE);
//
// // setup callback info
// timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallbackLo;
// timerConfig[timerIndex].edgeCallback[channelIndex + 1] = edgeCallbackHi;
// timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback;
// timerConfig[timerIndex].overflowCallback[channelIndex + 1] = NULL;
//
// // enable channel IRQs
// if (edgeCallbackLo) {
// TIM_ClearFlag(timHw->tim, TIM_IT_CCx(chLo));
// TIM_ITConfig(timHw->tim, TIM_IT_CCx(chLo), ENABLE);
// }
// if (edgeCallbackHi) {
// TIM_ClearFlag(timHw->tim, TIM_IT_CCx(chHi));
// TIM_ITConfig(timHw->tim, TIM_IT_CCx(chHi), ENABLE);
// }
//
// timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim);
//}
//
//// enable/disable IRQ for low channel in dual configuration
//void timerChITConfigDualLo(const timerHardware_t *timHw, FunctionalState newState) {
// TIM_ITConfig(timHw->tim, TIM_IT_CCx(timHw->channel&~TIM_Channel_2), newState);
//}
// enable or disable IRQ
void timerChITConfig(const timerHardware_t *timHw, FunctionalState newState)
@ -540,17 +497,6 @@ void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned
}
/* 获取输入通道极性 暂时没用*/
//void timerChICPolarity(const timerHardware_t *timHw, bool polarityRising)
//{
// timCCER_t tmpccer = timHw->tim->CCER;
// tmpccer &= ~(TIM_CCER_CC1P << timHw->channel);
// tmpccer |= polarityRising ? (TIM_ICPolarity_Rising << timHw->channel) : (TIM_ICPolarity_Falling << timHw->channel);
// timHw->tim->CCER = tmpccer;
//}
volatile timCCR_t* timerChCCR(const timerHardware_t *timHw)
{
@ -567,41 +513,6 @@ volatile timCCR_t* timerChCCR(const timerHardware_t *timHw)
}
//void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHigh)
//{
// TIM_OCInitTypeDef TIM_OCInitStructure;
//
// TIM_OCStructInit(&TIM_OCInitStructure);
// if (outEnable) {
// TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Inactive;
// TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
// if (timHw->output & TIMER_OUTPUT_INVERTED) {
// stateHigh = !stateHigh;
// }
// TIM_OCInitStructure.TIM_OCPolarity = stateHigh ? TIM_OCPolarity_High : TIM_OCPolarity_Low;
// } else {
// TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_Timing;
// }
//
// switch (timHw->channel) {
// case TIM_Channel_1:
// TIM_OC1Init(timHw->tim, &TIM_OCInitStructure);
// TIM_OC1PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
// break;
// case TIM_Channel_2:
// TIM_OC2Init(timHw->tim, &TIM_OCInitStructure);
// TIM_OC2PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
// break;
// case TIM_Channel_3:
// TIM_OC3Init(timHw->tim, &TIM_OCInitStructure);
// TIM_OC3PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
// break;
// case TIM_Channel_4:
// TIM_OC4Init(timHw->tim, &TIM_OCInitStructure);
// TIM_OC4PreloadConfig(timHw->tim, TIM_OCPreload_Disable);
// break;
// }
//}
static void timCCxHandler(tmr_type *tim, timerConfig_t *timerConfig)
{

View File

@ -166,6 +166,9 @@
#define MODIFY_REG(REG, CLEARMASK, SETMASK) WRITE_REG((REG), (((READ_REG(REG)) & (~(CLEARMASK))) | (SETMASK)))
#define FunctionalState confirm_state
#define ENABLE TRUE
#define DISABLE FALSE
#elif defined(SIMULATOR_BUILD)