Merge pull request #2161 from AlienWiiBF/F7LibFix

Cleanup F7 CMSIS and HAL Library compiler warnings
This commit is contained in:
MJ666 2017-01-19 00:21:46 -08:00 committed by GitHub
commit 3d6a331fc9
6 changed files with 89 additions and 6 deletions

View File

@ -332,9 +332,71 @@ else ifeq ($(TARGET),$(filter $(TARGET), $(F7_TARGETS)))
#STDPERIPH #STDPERIPH
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F7xx_HAL_Driver STDPERIPH_DIR = $(ROOT)/lib/main/STM32F7xx_HAL_Driver
STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/Src/*.c)) STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/Src/*.c))
EXCLUDES = stm32f7xx_hal_timebase_rtc_wakeup_template.c \ EXCLUDES = stm32f7xx_hal_can.c \
stm32f7xx_hal_cec.c \
stm32f7xx_hal_crc.c \
stm32f7xx_hal_crc_ex.c \
stm32f7xx_hal_cryp.c \
stm32f7xx_hal_cryp_ex.c \
stm32f7xx_hal_dac.c \
stm32f7xx_hal_dac_ex.c \
stm32f7xx_hal_dcmi.c \
stm32f7xx_hal_dcmi_ex.c \
stm32f7xx_hal_dfsdm.c \
stm32f7xx_hal_dma2d.c \
stm32f7xx_hal_dsi.c \
stm32f7xx_hal_eth.c \
stm32f7xx_hal_hash.c \
stm32f7xx_hal_hash_ex.c \
stm32f7xx_hal_hcd.c \
stm32f7xx_hal_i2s.c \
stm32f7xx_hal_irda.c \
stm32f7xx_hal_iwdg.c \
stm32f7xx_hal_jpeg.c \
stm32f7xx_hal_lptim.c \
stm32f7xx_hal_ltdc.c \
stm32f7xx_hal_ltdc_ex.c \
stm32f7xx_hal_mdios.c \
stm32f7xx_hal_mmc.c \
stm32f7xx_hal_msp_template.c \
stm32f7xx_hal_nand.c \
stm32f7xx_hal_nor.c \
stm32f7xx_hal_qspi.c \
stm32f7xx_hal_rng.c \
stm32f7xx_hal_rtc.c \
stm32f7xx_hal_rtc_ex.c \
stm32f7xx_hal_sai.c \
stm32f7xx_hal_sai_ex.c \
stm32f7xx_hal_sd.c \
stm32f7xx_hal_sdram.c \
stm32f7xx_hal_smartcard.c \
stm32f7xx_hal_smartcard_ex.c \
stm32f7xx_hal_smbus.c \
stm32f7xx_hal_spdifrx.c \
stm32f7xx_hal_sram.c \
stm32f7xx_hal_timebase_rtc_alarm_template.c \ stm32f7xx_hal_timebase_rtc_alarm_template.c \
stm32f7xx_hal_timebase_tim_template.c stm32f7xx_hal_timebase_rtc_wakeup_template.c \
stm32f7xx_hal_timebase_tim_template.c \
stm32f7xx_hal_wwdg.c \
stm32f7xx_ll_adc.c \
stm32f7xx_ll_crc.c \
stm32f7xx_ll_dac.c \
stm32f7xx_ll_dma.c \
stm32f7xx_ll_dma2d.c \
stm32f7xx_ll_exti.c \
stm32f7xx_ll_fmc.c \
stm32f7xx_ll_gpio.c \
stm32f7xx_ll_i2c.c \
stm32f7xx_ll_lptim.c \
stm32f7xx_ll_pwr.c \
stm32f7xx_ll_rcc.c \
stm32f7xx_ll_rng.c \
stm32f7xx_ll_rtc.c \
stm32f7xx_ll_sdmmc.c \
stm32f7xx_ll_spi.c \
stm32f7xx_ll_tim.c \
stm32f7xx_ll_usart.c \
stm32f7xx_ll_utils.c
STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))

View File

@ -756,6 +756,7 @@ HAL_StatusTypeDef HAL_ADCEx_MultiModeStop_DMA(ADC_HandleTypeDef* hadc)
*/ */
uint32_t HAL_ADCEx_MultiModeGetValue(ADC_HandleTypeDef* hadc) uint32_t HAL_ADCEx_MultiModeGetValue(ADC_HandleTypeDef* hadc)
{ {
UNUSED(hadc);
/* Return the multi mode conversion value */ /* Return the multi mode conversion value */
return ADC->CDR; return ADC->CDR;
} }

View File

@ -1258,7 +1258,7 @@ static HAL_StatusTypeDef PCD_WriteEmptyTxFifo(PCD_HandleTypeDef *hpcd, uint32_t
ep = &hpcd->IN_ep[epnum]; ep = &hpcd->IN_ep[epnum];
len = ep->xfer_len - ep->xfer_count; len = ep->xfer_len - ep->xfer_count;
if (len > ep->maxpacket) if (len > (int32_t)ep->maxpacket)
{ {
len = ep->maxpacket; len = ep->maxpacket;
} }
@ -1273,7 +1273,7 @@ static HAL_StatusTypeDef PCD_WriteEmptyTxFifo(PCD_HandleTypeDef *hpcd, uint32_t
/* Write the FIFO */ /* Write the FIFO */
len = ep->xfer_len - ep->xfer_count; len = ep->xfer_len - ep->xfer_count;
if (len > ep->maxpacket) if (len > (int32_t)ep->maxpacket)
{ {
len = ep->maxpacket; len = ep->maxpacket;
} }

View File

@ -404,6 +404,7 @@ void HAL_PWR_DisableWakeUpPin(uint32_t WakeUpPinx)
*/ */
void HAL_PWR_EnterSLEEPMode(uint32_t Regulator, uint8_t SLEEPEntry) void HAL_PWR_EnterSLEEPMode(uint32_t Regulator, uint8_t SLEEPEntry)
{ {
UNUSED(Regulator);
/* Check the parameters */ /* Check the parameters */
assert_param(IS_PWR_REGULATOR(Regulator)); assert_param(IS_PWR_REGULATOR(Regulator));
assert_param(IS_PWR_SLEEP_ENTRY(SLEEPEntry)); assert_param(IS_PWR_SLEEP_ENTRY(SLEEPEntry));

View File

@ -2125,7 +2125,8 @@ HAL_StatusTypeDef HAL_TIM_OnePulse_Start(TIM_HandleTypeDef *htim, uint32_t Outpu
No need to enable the counter, it's enabled automatically by hardware No need to enable the counter, it's enabled automatically by hardware
(the counter starts in response to a stimulus and generate a pulse */ (the counter starts in response to a stimulus and generate a pulse */
UNUSED(OutputChannel);
TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE); TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE);
TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE); TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE);
@ -2157,6 +2158,7 @@ HAL_StatusTypeDef HAL_TIM_OnePulse_Stop(TIM_HandleTypeDef *htim, uint32_t Output
if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output
in all combinations, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be disabled together */ in all combinations, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be disabled together */
UNUSED(OutputChannel);
TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE); TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE);
TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE); TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE);
@ -2194,6 +2196,7 @@ HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t Ou
No need to enable the counter, it's enabled automatically by hardware No need to enable the counter, it's enabled automatically by hardware
(the counter starts in response to a stimulus and generate a pulse */ (the counter starts in response to a stimulus and generate a pulse */
UNUSED(OutputChannel);
/* Enable the TIM Capture/Compare 1 interrupt */ /* Enable the TIM Capture/Compare 1 interrupt */
__HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1); __HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1);
@ -2225,6 +2228,7 @@ HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t Ou
*/ */
HAL_StatusTypeDef HAL_TIM_OnePulse_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel) HAL_StatusTypeDef HAL_TIM_OnePulse_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel)
{ {
UNUSED(OutputChannel);
/* Disable the TIM Capture/Compare 1 interrupt */ /* Disable the TIM Capture/Compare 1 interrupt */
__HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1); __HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1);

View File

@ -5,7 +5,7 @@
****************************************************************************** ******************************************************************************
* @attention * @attention
* *
* <h2><center>&copy; COPYRIGHT(c) 2016 STMicroelectronics</center></h2> * <h2><center>&copy; COPYRIGHT(c) 2017 STMicroelectronics</center></h2>
* *
* Redistribution and use in source and binary forms, with or without modification, * Redistribution and use in source and binary forms, with or without modification,
* are permitted provided that the following conditions are met: * are permitted provided that the following conditions are met:
@ -72,6 +72,7 @@
/* #define HAL_RTC_MODULE_ENABLED */ /* #define HAL_RTC_MODULE_ENABLED */
/* #define HAL_SAI_MODULE_ENABLED */ /* #define HAL_SAI_MODULE_ENABLED */
/* #define HAL_SD_MODULE_ENABLED */ /* #define HAL_SD_MODULE_ENABLED */
/* #define HAL_MMC_MODULE_ENABLED */
/* #define HAL_SPDIFRX_MODULE_ENABLED */ /* #define HAL_SPDIFRX_MODULE_ENABLED */
#define HAL_SPI_MODULE_ENABLED #define HAL_SPI_MODULE_ENABLED
#define HAL_TIM_MODULE_ENABLED #define HAL_TIM_MODULE_ENABLED
@ -86,6 +87,8 @@
/* #define HAL_DSI_MODULE_ENABLED */ /* #define HAL_DSI_MODULE_ENABLED */
/* #define HAL_JPEG_MODULE_ENABLED */ /* #define HAL_JPEG_MODULE_ENABLED */
/* #define HAL_MDIOS_MODULE_ENABLED */ /* #define HAL_MDIOS_MODULE_ENABLED */
/* #define HAL_SMBUS_MODULE_ENABLED */
/* #define HAL_MMC_MODULE_ENABLED */
#define HAL_GPIO_MODULE_ENABLED #define HAL_GPIO_MODULE_ENABLED
#define HAL_DMA_MODULE_ENABLED #define HAL_DMA_MODULE_ENABLED
#define HAL_RCC_MODULE_ENABLED #define HAL_RCC_MODULE_ENABLED
@ -355,6 +358,10 @@
#include "stm32f7xx_hal_sd.h" #include "stm32f7xx_hal_sd.h"
#endif /* HAL_SD_MODULE_ENABLED */ #endif /* HAL_SD_MODULE_ENABLED */
#ifdef HAL_MMC_MODULE_ENABLED
#include "stm32f7xx_hal_mmc.h"
#endif /* HAL_MMC_MODULE_ENABLED */
#ifdef HAL_SPDIFRX_MODULE_ENABLED #ifdef HAL_SPDIFRX_MODULE_ENABLED
#include "stm32f7xx_hal_spdifrx.h" #include "stm32f7xx_hal_spdifrx.h"
#endif /* HAL_SPDIFRX_MODULE_ENABLED */ #endif /* HAL_SPDIFRX_MODULE_ENABLED */
@ -411,6 +418,14 @@
#include "stm32f7xx_hal_mdios.h" #include "stm32f7xx_hal_mdios.h"
#endif /* HAL_MDIOS_MODULE_ENABLED */ #endif /* HAL_MDIOS_MODULE_ENABLED */
#ifdef HAL_SMBUS_MODULE_ENABLED
#include "stm32f7xx_hal_smbus.h"
#endif /* HAL_SMBUS_MODULE_ENABLED */
#ifdef HAL_MMC_MODULE_ENABLED
#include "stm32f7xx_hal_mmc.h"
#endif /* HAL_MMC_MODULE_ENABLED */
/* Exported macro ------------------------------------------------------------*/ /* Exported macro ------------------------------------------------------------*/
#ifdef USE_FULL_ASSERT #ifdef USE_FULL_ASSERT
/** /**