Don't use define checks on DEVICE_FOO macros (partner code)

The DEVICE_FOO macros are always defined (either 0 or 1).

This patch replaces any instances of a define check on a DEVICE_FOO
macro with value test instead.

Signed-off-by: Alastair D'Silva <alastair@d-silva.org>
pull/9370/head
Alastair D'Silva 2018-12-20 10:19:33 +11:00 committed by adbridge
parent fcc9bb7d4d
commit b0220082de
92 changed files with 127 additions and 138 deletions

View File

@ -38,7 +38,7 @@
* POSSIBILITY OF SUCH DAMAGE. * POSSIBILITY OF SUCH DAMAGE.
******************************************************************************/ ******************************************************************************/
#ifdef DEVICE_FLASH #if DEVICE_FLASH
#include "flash_api.h" #include "flash_api.h"
#include "flash_data.h" #include "flash_data.h"
#include "mbed_critical.h" #include "mbed_critical.h"

View File

@ -43,7 +43,7 @@
#include "adi_gpio_def.h" #include "adi_gpio_def.h"
#include "ADuCM302x_device.h" #include "ADuCM302x_device.h"
#ifdef DEVICE_INTERRUPTIN #if DEVICE_INTERRUPTIN
#define MAX_GPIO_LINES 16 #define MAX_GPIO_LINES 16
#define MAX_GPIO_PORTS ADI_GPIO_NUM_PORTS #define MAX_GPIO_PORTS ADI_GPIO_NUM_PORTS
@ -327,4 +327,4 @@ void gpio_irq_disable(gpio_irq_t *obj)
channel_ids[port][pin_num].int_enable = 0; channel_ids[port][pin_num].int_enable = 0;
} }
#endif // #ifdef DEVICE_INTERRUPTIN #endif // #if DEVICE_INTERRUPTIN

View File

@ -40,7 +40,7 @@
#include "sleep_api.h" #include "sleep_api.h"
#ifdef DEVICE_SLEEP #if DEVICE_SLEEP
#include "adi_pwr.h" #include "adi_pwr.h"
#include "adi_pwr_def.h" #include "adi_pwr_def.h"
@ -218,4 +218,4 @@ void hal_deepsleep(void)
pADI_CLKG0_CLK->CTL5 = 0; pADI_CLKG0_CLK->CTL5 = 0;
} }
#endif // #ifdef DEVICE_SLEEP #endif // #if DEVICE_SLEEP

View File

@ -38,7 +38,7 @@
* POSSIBILITY OF SUCH DAMAGE. * POSSIBILITY OF SUCH DAMAGE.
******************************************************************************/ ******************************************************************************/
#if defined(DEVICE_TRNG) #if DEVICE_TRNG
#include <stdlib.h> #include <stdlib.h>
#include <drivers/rng/adi_rng.h> #include <drivers/rng/adi_rng.h>

View File

@ -38,7 +38,7 @@
* POSSIBILITY OF SUCH DAMAGE. * POSSIBILITY OF SUCH DAMAGE.
******************************************************************************/ ******************************************************************************/
#ifdef DEVICE_FLASH #if DEVICE_FLASH
#include "flash_api.h" #include "flash_api.h"
#include "flash_data.h" #include "flash_data.h"
#include "mbed_critical.h" #include "mbed_critical.h"

View File

@ -42,7 +42,7 @@
#include "adi_gpio.h" #include "adi_gpio.h"
#include "adi_gpio_def.h" #include "adi_gpio_def.h"
#ifdef DEVICE_INTERRUPTIN #if DEVICE_INTERRUPTIN
#define MAX_GPIO_LINES 16 #define MAX_GPIO_LINES 16
#define MAX_GPIO_PORTS ADI_GPIO_NUM_PORTS #define MAX_GPIO_PORTS ADI_GPIO_NUM_PORTS
@ -326,4 +326,4 @@ void gpio_irq_disable(gpio_irq_t *obj)
channel_ids[port][pin_num].int_enable = 0; channel_ids[port][pin_num].int_enable = 0;
} }
#endif // #ifdef DEVICE_INTERRUPTIN #endif // #if DEVICE_INTERRUPTIN

View File

@ -40,7 +40,7 @@
#include "sleep_api.h" #include "sleep_api.h"
#ifdef DEVICE_SLEEP #if DEVICE_SLEEP
#include "adi_pwr.h" #include "adi_pwr.h"
#include "adi_pwr_def.h" #include "adi_pwr_def.h"
@ -253,4 +253,4 @@ void hal_deepsleep(void)
pADI_CLKG0_CLK->CTL5 = 0; pADI_CLKG0_CLK->CTL5 = 0;
} }
#endif // #ifdef DEVICE_SLEEP #endif // #if DEVICE_SLEEP

View File

@ -38,7 +38,7 @@
* POSSIBILITY OF SUCH DAMAGE. * POSSIBILITY OF SUCH DAMAGE.
******************************************************************************/ ******************************************************************************/
#if defined(DEVICE_TRNG) #if DEVICE_TRNG
#include <stdlib.h> #include <stdlib.h>
#include <adi_rng.h> #include <adi_rng.h>

View File

@ -503,7 +503,7 @@ void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_b
enable_usart(obj); enable_usart(obj);
} }
#ifdef DEVICE_SERIAL_FC #if DEVICE_SERIAL_FC
void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, PinName txflow) void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, PinName txflow)
{ {

View File

@ -283,7 +283,7 @@ void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_b
sysclk_enable_peripheral_clock(clockid); sysclk_enable_peripheral_clock(clockid);
} }
#ifdef DEVICE_SERIAL_FC #if DEVICE_SERIAL_FC
void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, PinName txflow) void serial_set_flow_control(serial_t *obj, FlowControl type, PinName rxflow, PinName txflow)
{ {
@ -783,4 +783,4 @@ void serial_rx_abort_asynch(serial_t *obj)
pSERIAL_S(obj)->actrec = false; pSERIAL_S(obj)->actrec = false;
} }
#endif #endif

View File

@ -34,7 +34,7 @@ extern const PinMap PinMap_PWM_OUT[];
#endif #endif
//*** SERIAL *** //*** SERIAL ***
#ifdef DEVICE_SERIAL #if DEVICE_SERIAL
extern const PinMap PinMap_UART_TX[]; extern const PinMap PinMap_UART_TX[];
extern const PinMap PinMap_UART_RX[]; extern const PinMap PinMap_UART_RX[];
extern const PinMap PinMap_UART_RTS[]; extern const PinMap PinMap_UART_RTS[];
@ -42,7 +42,7 @@ extern const PinMap PinMap_UART_CTS[];
#endif #endif
//*** SPI *** //*** SPI ***
#ifdef DEVICE_SPI #if DEVICE_SPI
extern const PinMap PinMap_SPI_MOSI[]; extern const PinMap PinMap_SPI_MOSI[];
extern const PinMap PinMap_SPI_MISO[]; extern const PinMap PinMap_SPI_MISO[];
extern const PinMap PinMap_SPI_SCLK[]; extern const PinMap PinMap_SPI_SCLK[];
@ -50,12 +50,12 @@ extern const PinMap PinMap_SPI_SSEL[];
#endif #endif
//*** ADC *** //*** ADC ***
#ifdef DEVICE_ANALOGIN #if DEVICE_ANALOGIN
extern const PinMap PinMap_ADC[]; extern const PinMap PinMap_ADC[];
#endif #endif
//*** DAC *** //*** DAC ***
#ifdef DEVICE_ANALOGOUT #if DEVICE_ANALOGOUT
extern const PinMap PinMap_DAC[]; extern const PinMap PinMap_DAC[];
#endif #endif

View File

@ -185,7 +185,7 @@ struct pwmout_s {
}; };
#endif // DEVICE_PWMOUT #endif // DEVICE_PWMOUT
#ifdef DEVICE_ANALOGIN #if DEVICE_ANALOGIN
#include "cy_sar.h" #include "cy_sar.h"
struct analogin_s { struct analogin_s {
@ -196,7 +196,7 @@ struct analogin_s {
}; };
#endif // DEVICE_ANALOGIN #endif // DEVICE_ANALOGIN
#ifdef DEVICE_ANALOGOUT #if DEVICE_ANALOGOUT
#include "cy_ctdac.h" #include "cy_ctdac.h"
struct dac_s { struct dac_s {
@ -206,7 +206,7 @@ struct dac_s {
}; };
#endif // DEVICE_ANALOGOUT #endif // DEVICE_ANALOGOUT
#ifdef DEVICE_FLASH #if DEVICE_FLASH
struct flash_s { struct flash_s {
/* nothing to be stored for now */ /* nothing to be stored for now */
void *dummy; void *dummy;

View File

@ -19,7 +19,7 @@
#include "device.h" #include "device.h"
#include "cy_syspm.h" #include "cy_syspm.h"
#ifdef DEVICE_SLEEP #if DEVICE_SLEEP
void hal_sleep(void) void hal_sleep(void)
{ {

View File

@ -22,7 +22,7 @@
* Reference: "K66 Sub-Family Reference Manual, Rev. 2", chapter 38 * Reference: "K66 Sub-Family Reference Manual, Rev. 2", chapter 38
*/ */
#if defined(DEVICE_TRNG) #if DEVICE_TRNG
#include <stdlib.h> #include <stdlib.h>
#include "cmsis.h" #include "cmsis.h"

View File

@ -18,7 +18,7 @@
* *
*/ */
#if defined(DEVICE_TRNG) #if DEVICE_TRNG
#include <stdlib.h> #include <stdlib.h>
#include "cmsis.h" #include "cmsis.h"

View File

@ -22,7 +22,7 @@
* Reference: "MKW41Z/31Z/21Z Reference Manual", chapter 43 * Reference: "MKW41Z/31Z/21Z Reference Manual", chapter 43
*/ */
#if defined(DEVICE_TRNG) #if DEVICE_TRNG
#include "fsl_trng.h" #include "fsl_trng.h"
#include "trng_api.h" #include "trng_api.h"

View File

@ -18,7 +18,7 @@
* *
*/ */
#if defined(DEVICE_TRNG) #if DEVICE_TRNG
#include <stdlib.h> #include <stdlib.h>
#include "cmsis.h" #include "cmsis.h"

View File

@ -18,7 +18,7 @@
* *
*/ */
#if defined(DEVICE_TRNG) #if DEVICE_TRNG
#include <stdlib.h> #include <stdlib.h>
#include "cmsis.h" #include "cmsis.h"

View File

@ -18,7 +18,7 @@
#include "drivers/fsl_crc.h" #include "drivers/fsl_crc.h"
#include "platform/mbed_assert.h" #include "platform/mbed_assert.h"
#ifdef DEVICE_CRC #if DEVICE_CRC
static crc_bits_t width; static crc_bits_t width;
static uint32_t final_xor; static uint32_t final_xor;

View File

@ -22,7 +22,7 @@
* Reference: "K64 Sub-Family Reference Manual, Rev. 2", chapter 34 * Reference: "K64 Sub-Family Reference Manual, Rev. 2", chapter 34
*/ */
#if defined(DEVICE_TRNG) #if DEVICE_TRNG
#include <stdlib.h> #include <stdlib.h>
#include "cmsis.h" #include "cmsis.h"

View File

@ -27,12 +27,12 @@ extern const int GD_GPIO_MODE[];
extern const int GD_GPIO_SPEED[]; extern const int GD_GPIO_SPEED[];
/* ADC */ /* ADC */
#ifdef DEVICE_ANALOGIN #if DEVICE_ANALOGIN
extern const PinMap PinMap_ADC[]; extern const PinMap PinMap_ADC[];
#endif #endif
/* DAC */ /* DAC */
#ifdef DEVICE_ANALOGOUT #if DEVICE_ANALOGOUT
extern const PinMap PinMap_DAC[]; extern const PinMap PinMap_DAC[];
#endif #endif
@ -48,17 +48,17 @@ extern const PinMap PinMap_PWM[];
#endif #endif
/* SERIAL */ /* SERIAL */
#ifdef DEVICE_SERIAL #if DEVICE_SERIAL
extern const PinMap PinMap_UART_TX[]; extern const PinMap PinMap_UART_TX[];
extern const PinMap PinMap_UART_RX[]; extern const PinMap PinMap_UART_RX[];
#ifdef DEVICE_SERIAL_FC #if DEVICE_SERIAL_FC
extern const PinMap PinMap_UART_RTS[]; extern const PinMap PinMap_UART_RTS[];
extern const PinMap PinMap_UART_CTS[]; extern const PinMap PinMap_UART_CTS[];
#endif #endif
#endif #endif
/* SPI */ /* SPI */
#ifdef DEVICE_SPI #if DEVICE_SPI
extern const PinMap PinMap_SPI_MOSI[]; extern const PinMap PinMap_SPI_MOSI[];
extern const PinMap PinMap_SPI_MISO[]; extern const PinMap PinMap_SPI_MISO[];
extern const PinMap PinMap_SPI_SCLK[]; extern const PinMap PinMap_SPI_SCLK[];
@ -66,7 +66,7 @@ extern const PinMap PinMap_SPI_SSEL[];
#endif #endif
/* CAN */ /* CAN */
#ifdef DEVICE_CAN #if DEVICE_CAN
extern const PinMap PinMap_CAN_RD[]; extern const PinMap PinMap_CAN_RD[];
extern const PinMap PinMap_CAN_TD[]; extern const PinMap PinMap_CAN_TD[];
#endif #endif

View File

@ -74,7 +74,7 @@ void rtc_init(void)
MXC_PWRSEQ->reg0 |= MXC_F_PWRSEQ_REG0_PWR_RTCEN_RUN; MXC_PWRSEQ->reg0 |= MXC_F_PWRSEQ_REG0_PWR_RTCEN_RUN;
// Prepare interrupt handlers // Prepare interrupt handlers
#ifdef DEVICE_LPTICKER #if DEVICE_LPTICKER
NVIC_SetVector(RTC0_IRQn, (uint32_t)lp_ticker_irq_handler); NVIC_SetVector(RTC0_IRQn, (uint32_t)lp_ticker_irq_handler);
NVIC_EnableIRQ(RTC0_IRQn); NVIC_EnableIRQ(RTC0_IRQn);
#endif #endif

View File

@ -19,7 +19,7 @@
#include "pinmap.h" #include "pinmap.h"
#include "nrf_drv_adc.h" #include "nrf_drv_adc.h"
#ifdef DEVICE_ANALOGIN #if DEVICE_ANALOGIN
#define ADC_10BIT_RANGE 0x3FF #define ADC_10BIT_RANGE 0x3FF

View File

@ -36,7 +36,7 @@
* *
*/ */
#if (defined(DEVICE_FLASH) && defined(DEVICE_LPTICKER)) #if DEVICE_FLASH && DEVICE_LPTICKER
#include "hal/flash_api.h" #include "hal/flash_api.h"
#include "hal/lp_ticker_api.h" #include "hal/lp_ticker_api.h"

View File

@ -39,7 +39,7 @@
#include "i2c_api.h" #include "i2c_api.h"
#if (defined(DEVICE_I2C) && defined(DEVICE_LPTICKER)) #if DEVICE_I2C && DEVICE_LPTICKER
#include "mbed_assert.h" #include "mbed_assert.h"
#include "mbed_error.h" #include "mbed_error.h"

View File

@ -36,7 +36,7 @@
* *
*/ */
#if (defined(DEVICE_TRNG) && defined(DEVICE_LPTICKER)) #if DEVICE_TRNG && DEVICE_LPTICKER
#include "hal/trng_api.h" #include "hal/trng_api.h"
#include "hal/lp_ticker_api.h" #include "hal/lp_ticker_api.h"

View File

@ -222,7 +222,7 @@ void SystemInit(void)
* *
* The ITM has to be initialized before the SoftDevice which weren't guaranteed using the normal API. * The ITM has to be initialized before the SoftDevice which weren't guaranteed using the normal API.
*/ */
#if defined (DEVICE_ITM) #if DEVICE_ITM
/* Enable SWO trace functionality */ /* Enable SWO trace functionality */
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
NRF_CLOCK->TRACECONFIG |= CLOCK_TRACECONFIG_TRACEMUX_Serial << CLOCK_TRACECONFIG_TRACEMUX_Pos; NRF_CLOCK->TRACECONFIG |= CLOCK_TRACECONFIG_TRACEMUX_Serial << CLOCK_TRACECONFIG_TRACEMUX_Pos;

View File

@ -198,7 +198,7 @@ void SystemInit(void)
* *
* The ITM has to be initialized before the SoftDevice which weren't guaranteed using the normal API. * The ITM has to be initialized before the SoftDevice which weren't guaranteed using the normal API.
*/ */
#if defined (DEVICE_ITM) #if DEVICE_ITM
/* Enable SWO trace functionality */ /* Enable SWO trace functionality */
CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
NRF_CLOCK->TRACECONFIG |= CLOCK_TRACECONFIG_TRACEMUX_Serial << CLOCK_TRACECONFIG_TRACEMUX_Pos; NRF_CLOCK->TRACECONFIG |= CLOCK_TRACECONFIG_TRACEMUX_Serial << CLOCK_TRACECONFIG_TRACEMUX_Pos;

View File

@ -14,7 +14,7 @@
* limitations under the License. * limitations under the License.
*/ */
#ifdef DEVICE_ANALOGIN #if DEVICE_ANALOGIN
#include "hal/analogin_api.h" #include "hal/analogin_api.h"
#include "pinmap.h" #include "pinmap.h"

View File

@ -36,7 +36,7 @@
* *
*/ */
#if (defined(DEVICE_FLASH) && defined(DEVICE_LPTICKER)) #if DEVICE_FLASH && DEVICE_LPTICKER
#include "hal/flash_api.h" #include "hal/flash_api.h"
#include "hal/lp_ticker_api.h" #include "hal/lp_ticker_api.h"

View File

@ -36,7 +36,7 @@
* *
*/ */
#if (defined(DEVICE_I2C) && defined(DEVICE_LPTICKER)) #if DEVICE_I2C && DEVICE_LPTICKER
/* I2C /* I2C
* *
* This HAL implementation uses the nrf_drv_twi.h API primarily but switches to TWI for the * This HAL implementation uses the nrf_drv_twi.h API primarily but switches to TWI for the

View File

@ -14,7 +14,7 @@
* limitations under the License. * limitations under the License.
*/ */
#if defined(DEVICE_ITM) #if DEVICE_ITM
#include "hal/itm_api.h" #include "hal/itm_api.h"

View File

@ -36,7 +36,7 @@
* *
*/ */
#if defined(DEVICE_TRNG) #if DEVICE_TRNG
#if !defined(FEATURE_CRYPTOCELL310) #if !defined(FEATURE_CRYPTOCELL310)
#include "hal/trng_api.h" #include "hal/trng_api.h"
#include "hal/critical_section_api.h" #include "hal/critical_section_api.h"

View File

@ -59,13 +59,13 @@ struct spi_s {
uint8_t bits; uint8_t bits;
}; };
#if defined(DEVICE_FLASH) #if DEVICE_FLASH
struct flash_s { struct flash_s {
uint8_t dummy; uint8_t dummy;
}; };
#endif #endif
#if defined(DEVICE_TRNG) #if DEVICE_TRNG
struct trng_s { struct trng_s {
uint8_t dummy; uint8_t dummy;
}; };

View File

@ -117,7 +117,7 @@ void fIrqUart2Handler(void)
Uart2_Irq(); Uart2_Irq();
} }
#ifdef DEVICE_RTC #if DEVICE_RTC
/** Call the RTC IRQ handler */ /** Call the RTC IRQ handler */
void fIrqRtcHandler(void) void fIrqRtcHandler(void)
{ {

View File

@ -42,7 +42,7 @@
* *
*/ */
#ifdef DEVICE_RTC #if DEVICE_RTC
#include "rtc.h" #include "rtc.h"
#include "mbed_assert.h" #include "mbed_assert.h"

View File

@ -18,7 +18,7 @@
* *
*/ */
#if defined(DEVICE_TRNG) #if DEVICE_TRNG
#include "cmsis.h" #include "cmsis.h"
#include "trng_api.h" #include "trng_api.h"

View File

@ -14,7 +14,7 @@
* limitations under the License. * limitations under the License.
*/ */
#if defined(DEVICE_TRNG) #if DEVICE_TRNG
#include "drivers/I2C.h" #include "drivers/I2C.h"
#include "platform/mbed_wait_api.h" #include "platform/mbed_wait_api.h"

View File

@ -14,7 +14,7 @@
* limitations under the License. * limitations under the License.
*/ */
#if defined(DEVICE_TRNG) #if DEVICE_TRNG
#include "trng_api.h" #include "trng_api.h"
#if defined(TARGET_GR_LYCHEE) #if defined(TARGET_GR_LYCHEE)

View File

@ -21,7 +21,7 @@
#include "platform_stdlib.h" #include "platform_stdlib.h"
#endif #endif
#ifdef DEVICE_TRNG #if DEVICE_TRNG
void trng_init(trng_t *obj) void trng_init(trng_t *obj)

View File

@ -35,13 +35,13 @@
#include "PeripheralNames.h" #include "PeripheralNames.h"
//*** ADC *** //*** ADC ***
#ifdef DEVICE_ANALOGIN #if DEVICE_ANALOGIN
extern const PinMap PinMap_ADC[]; extern const PinMap PinMap_ADC[];
extern const PinMap PinMap_ADC_Internal[]; extern const PinMap PinMap_ADC_Internal[];
#endif #endif
//*** DAC *** //*** DAC ***
#ifdef DEVICE_ANALOGOUT #if DEVICE_ANALOGOUT
extern const PinMap PinMap_DAC[]; extern const PinMap PinMap_DAC[];
#endif #endif
@ -57,17 +57,17 @@ extern const PinMap PinMap_PWM[];
#endif #endif
//*** SERIAL *** //*** SERIAL ***
#ifdef DEVICE_SERIAL #if DEVICE_SERIAL
extern const PinMap PinMap_UART_TX[]; extern const PinMap PinMap_UART_TX[];
extern const PinMap PinMap_UART_RX[]; extern const PinMap PinMap_UART_RX[];
#ifdef DEVICE_SERIAL_FC #if DEVICE_SERIAL_FC
extern const PinMap PinMap_UART_RTS[]; extern const PinMap PinMap_UART_RTS[];
extern const PinMap PinMap_UART_CTS[]; extern const PinMap PinMap_UART_CTS[];
#endif #endif
#endif #endif
//*** SPI *** //*** SPI ***
#ifdef DEVICE_SPI #if DEVICE_SPI
extern const PinMap PinMap_SPI_MOSI[]; extern const PinMap PinMap_SPI_MOSI[];
extern const PinMap PinMap_SPI_MISO[]; extern const PinMap PinMap_SPI_MISO[];
extern const PinMap PinMap_SPI_SCLK[]; extern const PinMap PinMap_SPI_SCLK[];
@ -75,12 +75,12 @@ extern const PinMap PinMap_SPI_SSEL[];
#endif #endif
//*** CAN *** //*** CAN ***
#ifdef DEVICE_CAN #if DEVICE_CAN
extern const PinMap PinMap_CAN_RD[]; extern const PinMap PinMap_CAN_RD[];
extern const PinMap PinMap_CAN_TD[]; extern const PinMap PinMap_CAN_TD[];
#endif #endif
#ifdef DEVICE_QSPI #if DEVICE_QSPI
extern const PinMap PinMap_QSPI_DATA[]; extern const PinMap PinMap_QSPI_DATA[];
extern const PinMap PinMap_QSPI_SCLK[]; extern const PinMap PinMap_QSPI_SCLK[];
extern const PinMap PinMap_QSPI_SSEL[]; extern const PinMap PinMap_QSPI_SSEL[];

View File

@ -23,7 +23,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_CAN #if DEVICE_CAN
#define CAN_NUM 1 // Number of CAN peripherals present in the STM32 serie #define CAN_NUM 1 // Number of CAN peripherals present in the STM32 serie

View File

@ -57,7 +57,7 @@ struct spi_s {
PinName pin_mosi; PinName pin_mosi;
PinName pin_sclk; PinName pin_sclk;
PinName pin_ssel; PinName pin_ssel;
#ifdef DEVICE_SPI_ASYNCH #if DEVICE_SPI_ASYNCH
uint32_t event; uint32_t event;
uint8_t transfer_type; uint8_t transfer_type;
#endif #endif

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_I2C #if DEVICE_I2C
#if defined I2C1_BASE #if defined I2C1_BASE
#define I2C1_EV_IRQn I2C1_IRQn #define I2C1_EV_IRQn I2C1_IRQn

View File

@ -31,7 +31,7 @@
#include "pwmout_api.h" #include "pwmout_api.h"
#include "pwmout_device.h" #include "pwmout_device.h"
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
const pwm_apb_map_t pwm_apb_map_table[] = { const pwm_apb_map_t pwm_apb_map_table[] = {
#if defined(TIM2_BASE) #if defined(TIM2_BASE)

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
typedef enum { typedef enum {
PWMOUT_ON_APB1 = 0, PWMOUT_ON_APB1 = 0,

View File

@ -23,7 +23,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_CAN #if DEVICE_CAN
#define CAN_NUM 1 // Number of CAN peripherals present in the STM32 serie #define CAN_NUM 1 // Number of CAN peripherals present in the STM32 serie

View File

@ -76,7 +76,7 @@ struct spi_s {
PinName pin_mosi; PinName pin_mosi;
PinName pin_sclk; PinName pin_sclk;
PinName pin_ssel; PinName pin_ssel;
#ifdef DEVICE_SPI_ASYNCH #if DEVICE_SPI_ASYNCH
uint32_t event; uint32_t event;
uint8_t transfer_type; uint8_t transfer_type;
#endif #endif

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_I2C #if DEVICE_I2C
/* Define IP version */ /* Define IP version */
#define I2C_IP_VERSION_V1 #define I2C_IP_VERSION_V1

View File

@ -31,7 +31,7 @@
#include "pwmout_api.h" #include "pwmout_api.h"
#include "pwmout_device.h" #include "pwmout_device.h"
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
const pwm_apb_map_t pwm_apb_map_table[] = { const pwm_apb_map_t pwm_apb_map_table[] = {
#if defined(TIM1_BASE) #if defined(TIM1_BASE)

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
typedef enum { typedef enum {
PWMOUT_ON_APB1 = 0, PWMOUT_ON_APB1 = 0,

View File

@ -23,7 +23,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_CAN #if DEVICE_CAN
#define CAN_NUM 2 // Number of CAN peripherals present in the STM32 serie #define CAN_NUM 2 // Number of CAN peripherals present in the STM32 serie

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_I2C #if DEVICE_I2C
#define I2C_IP_VERSION_V1 #define I2C_IP_VERSION_V1

View File

@ -94,7 +94,7 @@ struct spi_s {
PinName pin_mosi; PinName pin_mosi;
PinName pin_sclk; PinName pin_sclk;
PinName pin_ssel; PinName pin_ssel;
#ifdef DEVICE_SPI_ASYNCH #if DEVICE_SPI_ASYNCH
uint32_t event; uint32_t event;
uint8_t transfer_type; uint8_t transfer_type;
#endif #endif
@ -137,7 +137,7 @@ struct pwmout_s {
uint8_t inverted; uint8_t inverted;
}; };
#ifdef DEVICE_CAN #if DEVICE_CAN
struct can_s { struct can_s {
CAN_HandleTypeDef CanHandle; CAN_HandleTypeDef CanHandle;
int index; int index;

View File

@ -31,7 +31,7 @@
#include "pwmout_api.h" #include "pwmout_api.h"
#include "pwmout_device.h" #include "pwmout_device.h"
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
const pwm_apb_map_t pwm_apb_map_table[] = { const pwm_apb_map_t pwm_apb_map_table[] = {
#if defined(TIM2_BASE) #if defined(TIM2_BASE)

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
typedef enum { typedef enum {
PWMOUT_ON_APB1 = 0, PWMOUT_ON_APB1 = 0,

View File

@ -23,7 +23,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_CAN #if DEVICE_CAN
#define CAN_NUM 1 // Number of CAN peripherals present in the STM32 serie #define CAN_NUM 1 // Number of CAN peripherals present in the STM32 serie

View File

@ -57,7 +57,7 @@ struct spi_s {
PinName pin_mosi; PinName pin_mosi;
PinName pin_sclk; PinName pin_sclk;
PinName pin_ssel; PinName pin_ssel;
#ifdef DEVICE_SPI_ASYNCH #if DEVICE_SPI_ASYNCH
uint32_t event; uint32_t event;
uint8_t transfer_type; uint8_t transfer_type;
#endif #endif

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_I2C #if DEVICE_I2C
#define I2C_IP_VERSION_V2 #define I2C_IP_VERSION_V2

View File

@ -31,7 +31,7 @@
#include "pwmout_api.h" #include "pwmout_api.h"
#include "pwmout_device.h" #include "pwmout_device.h"
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
const pwm_apb_map_t pwm_apb_map_table[] = { const pwm_apb_map_t pwm_apb_map_table[] = {
#if defined(TIM2_BASE) #if defined(TIM2_BASE)

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
typedef enum { typedef enum {
PWMOUT_ON_APB1 = 0, PWMOUT_ON_APB1 = 0,

View File

@ -411,7 +411,7 @@ int OdinWiFiInterface::scan(WiFiAccessPoint *res_list, unsigned count)
return found_aps; return found_aps;
} }
#ifdef DEVICE_WIFI_AP #if DEVICE_WIFI_AP
nsapi_error_t OdinWiFiInterface::set_ap_network(const char *ip_address, const char *netmask, const char *gateway) nsapi_error_t OdinWiFiInterface::set_ap_network(const char *ip_address, const char *netmask, const char *gateway)
{ {
@ -1044,10 +1044,6 @@ void OdinWiFiInterface::handle_wlan_status_started(wlan_status_started_s *start)
start->info.macAddress[4], start->info.macAddress[4],
start->info.macAddress[5]); start->info.macAddress[5]);
if(!_wlan_initialized) {
//Initialize network stack interface without activating it
}
if (!_interface) { if (!_interface) {
nsapi_error_t error_code = _stack.add_ethernet_interface(_emac, true, &_interface); nsapi_error_t error_code = _stack.add_ethernet_interface(_emac, true, &_interface);
if (error_code != NSAPI_ERROR_OK) { if (error_code != NSAPI_ERROR_OK) {
@ -1058,16 +1054,9 @@ void OdinWiFiInterface::handle_wlan_status_started(wlan_status_started_s *start)
} }
} }
#ifdef DEVICE_WIFI_AP
if(!_wlan_initialized) {
_wlan_initialized = true;
}
#else
if (!_wlan_initialized) { if (!_wlan_initialized) {
_wlan_initialized = true; _wlan_initialized = true;
} }
#endif
// The OdinWifiInterface object is now fully initialized // The OdinWifiInterface object is now fully initialized
_state = S_STARTED; _state = S_STARTED;

View File

@ -18,7 +18,7 @@
#define ODIN_WIFI_INTERFACE_H #define ODIN_WIFI_INTERFACE_H
#include "WiFiInterface.h" #include "WiFiInterface.h"
#ifdef DEVICE_WIFI_AP #if DEVICE_WIFI_AP
#include "UbloxWiFiSoftAPInterface.h" #include "UbloxWiFiSoftAPInterface.h"
#endif #endif
@ -46,7 +46,7 @@ struct wlan_scan_indication_s;
/** OdinWiFiInterface class /** OdinWiFiInterface class
* Implementation of the WiFiInterface for the ODIN-W2 module * Implementation of the WiFiInterface for the ODIN-W2 module
*/ */
#ifdef DEVICE_WIFI_AP #if DEVICE_WIFI_AP
class OdinWiFiInterface : public WiFiInterface, public UbloxWiFiSoftAPInterface, public EMACInterface class OdinWiFiInterface : public WiFiInterface, public UbloxWiFiSoftAPInterface, public EMACInterface
#else #else
class OdinWiFiInterface : public WiFiInterface, public EMACInterface class OdinWiFiInterface : public WiFiInterface, public EMACInterface
@ -141,7 +141,7 @@ public:
*/ */
virtual nsapi_error_t set_timeout(int ms); virtual nsapi_error_t set_timeout(int ms);
#ifdef DEVICE_WIFI_AP #if DEVICE_WIFI_AP
/** Set IP config for access point /** Set IP config for access point
* *

View File

@ -23,7 +23,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_CAN #if DEVICE_CAN
#if defined(CAN3_BASE) #if defined(CAN3_BASE)

View File

@ -76,7 +76,7 @@ struct spi_s {
PinName pin_mosi; PinName pin_mosi;
PinName pin_sclk; PinName pin_sclk;
PinName pin_ssel; PinName pin_ssel;
#ifdef DEVICE_SPI_ASYNCH #if DEVICE_SPI_ASYNCH
uint32_t event; uint32_t event;
uint8_t transfer_type; uint8_t transfer_type;
#endif #endif

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_I2C #if DEVICE_I2C
/* Define IP version */ /* Define IP version */
#define I2C_IP_VERSION_V1 #define I2C_IP_VERSION_V1

View File

@ -31,7 +31,7 @@
#include "pwmout_api.h" #include "pwmout_api.h"
#include "pwmout_device.h" #include "pwmout_device.h"
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
const pwm_apb_map_t pwm_apb_map_table[] = { const pwm_apb_map_t pwm_apb_map_table[] = {
#if defined(TIM2_BASE) #if defined(TIM2_BASE)

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
typedef enum { typedef enum {
PWMOUT_ON_APB1 = 0, PWMOUT_ON_APB1 = 0,

View File

@ -23,7 +23,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_CAN #if DEVICE_CAN
#if defined(CAN3_BASE) #if defined(CAN3_BASE)

View File

@ -57,7 +57,7 @@ struct spi_s {
PinName pin_mosi; PinName pin_mosi;
PinName pin_sclk; PinName pin_sclk;
PinName pin_ssel; PinName pin_ssel;
#ifdef DEVICE_SPI_ASYNCH #if DEVICE_SPI_ASYNCH
uint32_t event; uint32_t event;
uint8_t transfer_type; uint8_t transfer_type;
#endif #endif

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_I2C #if DEVICE_I2C
#define I2C_IP_VERSION_V2 #define I2C_IP_VERSION_V2

View File

@ -31,7 +31,7 @@
#include "pwmout_api.h" #include "pwmout_api.h"
#include "pwmout_device.h" #include "pwmout_device.h"
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
const pwm_apb_map_t pwm_apb_map_table[] = { const pwm_apb_map_t pwm_apb_map_table[] = {
#if defined(TIM2_BASE) #if defined(TIM2_BASE)

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
typedef enum { typedef enum {
PWMOUT_ON_APB1 = 0, PWMOUT_ON_APB1 = 0,

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_I2C #if DEVICE_I2C
#define I2C_IP_VERSION_V2 #define I2C_IP_VERSION_V2

View File

@ -31,7 +31,7 @@
#include "pwmout_api.h" #include "pwmout_api.h"
#include "pwmout_device.h" #include "pwmout_device.h"
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
const pwm_apb_map_t pwm_apb_map_table[] = { const pwm_apb_map_t pwm_apb_map_table[] = {
#if defined(TIM2_BASE) #if defined(TIM2_BASE)

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
#define PWMOUT_INVERTED_NOT_SUPPORTED #define PWMOUT_INVERTED_NOT_SUPPORTED

View File

@ -76,7 +76,7 @@ struct spi_s {
PinName pin_mosi; PinName pin_mosi;
PinName pin_sclk; PinName pin_sclk;
PinName pin_ssel; PinName pin_ssel;
#ifdef DEVICE_SPI_ASYNCH #if DEVICE_SPI_ASYNCH
uint32_t event; uint32_t event;
uint8_t transfer_type; uint8_t transfer_type;
#endif #endif

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_I2C #if DEVICE_I2C
/* Define IP version */ /* Define IP version */
#define I2C_IP_VERSION_V1 #define I2C_IP_VERSION_V1

View File

@ -31,7 +31,7 @@
#include "pwmout_api.h" #include "pwmout_api.h"
#include "pwmout_device.h" #include "pwmout_device.h"
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
const pwm_apb_map_t pwm_apb_map_table[] = { const pwm_apb_map_t pwm_apb_map_table[] = {
#if defined(TIM2_BASE) #if defined(TIM2_BASE)

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
/* L1 HAL do not offer Output Compare idle nor inverted mode*/ /* L1 HAL do not offer Output Compare idle nor inverted mode*/
#define PWMOUT_INVERTED_NOT_SUPPORTED #define PWMOUT_INVERTED_NOT_SUPPORTED

View File

@ -23,7 +23,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_CAN #if DEVICE_CAN
#define CAN_NUM 1 // Number of CAN peripherals present in the STM32 serie #define CAN_NUM 1 // Number of CAN peripherals present in the STM32 serie

View File

@ -57,7 +57,7 @@ struct spi_s {
PinName pin_mosi; PinName pin_mosi;
PinName pin_sclk; PinName pin_sclk;
PinName pin_ssel; PinName pin_ssel;
#ifdef DEVICE_SPI_ASYNCH #if DEVICE_SPI_ASYNCH
uint32_t event; uint32_t event;
uint8_t transfer_type; uint8_t transfer_type;
#endif #endif

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_I2C #if DEVICE_I2C
#define I2C_IP_VERSION_V2 #define I2C_IP_VERSION_V2

View File

@ -31,7 +31,7 @@
#include "pwmout_api.h" #include "pwmout_api.h"
#include "pwmout_device.h" #include "pwmout_device.h"
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
const pwm_apb_map_t pwm_apb_map_table[] = { const pwm_apb_map_t pwm_apb_map_table[] = {
#if defined(TIM2_BASE) #if defined(TIM2_BASE)

View File

@ -36,7 +36,7 @@
extern "C" { extern "C" {
#endif #endif
#ifdef DEVICE_PWMOUT #if DEVICE_PWMOUT
typedef enum { typedef enum {
PWMOUT_ON_APB1 = 0, PWMOUT_ON_APB1 = 0,

View File

@ -3,7 +3,7 @@
#include "platform/mbed_assert.h" #include "platform/mbed_assert.h"
#ifdef DEVICE_CRC #if DEVICE_CRC
static CRC_HandleTypeDef current_state; static CRC_HandleTypeDef current_state;
static uint32_t final_xor; static uint32_t final_xor;

View File

@ -530,7 +530,7 @@ int spi_busy(spi_t *obj)
return ssp_busy(obj); return ssp_busy(obj);
} }
#ifdef DEVICE_SPI_ASYNCH #if DEVICE_SPI_ASYNCH
typedef enum { typedef enum {
SPI_TRANSFER_TYPE_NONE = 0, SPI_TRANSFER_TYPE_NONE = 0,
SPI_TRANSFER_TYPE_TX = 1, SPI_TRANSFER_TYPE_TX = 1,

View File

@ -18,7 +18,7 @@
* *
*/ */
#if defined(DEVICE_TRNG) #if DEVICE_TRNG
#include <stdlib.h> #include <stdlib.h>
#include "cmsis.h" #include "cmsis.h"

View File

@ -441,7 +441,7 @@ void i2c_slave_address(i2c_t *obj, int idx, uint32_t address, uint32_t mask)
#endif //DEVICE_I2CSLAVE #endif //DEVICE_I2CSLAVE
#ifdef DEVICE_I2C_ASYNCH #if DEVICE_I2C_ASYNCH
#include "em_dma.h" #include "em_dma.h"
#include "dma_api_HAL.h" #include "dma_api_HAL.h"

View File

@ -14,7 +14,7 @@
* limitations under the License. * limitations under the License.
*/ */
#if defined(DEVICE_ITM) #if DEVICE_ITM
#include "hal/itm_api.h" #include "hal/itm_api.h"
#include "cmsis.h" #include "cmsis.h"

View File

@ -24,7 +24,7 @@
#include "trng_api.h" #include "trng_api.h"
#include "sl_trng.h" #include "sl_trng.h"
#if defined(DEVICE_TRNG) #if DEVICE_TRNG
static bool is_trng_enabled = false; static bool is_trng_enabled = false;
void trng_init(trng_t *obj) void trng_init(trng_t *obj)

View File

@ -28,7 +28,7 @@ from argparse import RawTextHelpFormatter
GENPINMAP_VERSION = "1.3" GENPINMAP_VERSION = "1.3"
ADD_DEVICE_IFDEF = 0 ADD_DEVICE_IF = 0
ADD_QSPI_FEATURE = 1 ADD_QSPI_FEATURE = 1
mcu_file="" mcu_file=""
@ -485,8 +485,8 @@ def print_list_header(comment, name, l, switch):
s += "// You have to comment all PWM using TIM_MST defined in hal_tick.h file\n" s += "// You have to comment all PWM using TIM_MST defined in hal_tick.h file\n"
s += "// or update python script (check TIM_MST_LIST) and re-run it\n" s += "// or update python script (check TIM_MST_LIST) and re-run it\n"
if ADD_DEVICE_IFDEF: if ADD_DEVICE_IF:
s += "#ifdef DEVICE_%s\n" % switch s += "#if DEVICE_%s\n" % switch
s += "MBED_WEAK const PinMap PinMap_%s[] = {\n" % name s += "MBED_WEAK const PinMap PinMap_%s[] = {\n" % name
@ -541,7 +541,7 @@ MBED_WEAK const PinMap PinMap_ADC_Internal[] = {
{NC, NC, 0} {NC, NC, 0}
}; };
""") """)
if ADD_DEVICE_IFDEF: if ADD_DEVICE_IF:
out_c_file.write( "#endif\n" ) out_c_file.write( "#endif\n" )
def print_dac(): def print_dac():
@ -568,7 +568,7 @@ def print_dac():
out_c_file.write( """ {NC, NC, 0} out_c_file.write( """ {NC, NC, 0}
}; };
""") """)
if ADD_DEVICE_IFDEF: if ADD_DEVICE_IF:
out_c_file.write( "#endif\n" ) out_c_file.write( "#endif\n" )
def print_i2c(l): def print_i2c(l):
@ -610,7 +610,7 @@ def print_i2c(l):
out_c_file.write( """ {NC, NC, 0} out_c_file.write( """ {NC, NC, 0}
}; };
""") """)
if ADD_DEVICE_IFDEF: if ADD_DEVICE_IF:
out_c_file.write( "#endif\n" ) out_c_file.write( "#endif\n" )
def print_pwm(): def print_pwm():
@ -662,7 +662,7 @@ def print_pwm():
out_c_file.write( """ {NC, NC, 0} out_c_file.write( """ {NC, NC, 0}
}; };
""") """)
if ADD_DEVICE_IFDEF: if ADD_DEVICE_IF:
out_c_file.write( "#endif\n" ) out_c_file.write( "#endif\n" )
def print_uart(l): def print_uart(l):
@ -703,7 +703,7 @@ def print_uart(l):
out_c_file.write( """ {NC, NC, 0} out_c_file.write( """ {NC, NC, 0}
}; };
""") """)
if ADD_DEVICE_IFDEF: if ADD_DEVICE_IF:
out_c_file.write( "#endif\n" ) out_c_file.write( "#endif\n" )
def print_spi(l): def print_spi(l):
@ -741,7 +741,7 @@ def print_spi(l):
out_c_file.write( """ {NC, NC, 0} out_c_file.write( """ {NC, NC, 0}
}; };
""") """)
if ADD_DEVICE_IFDEF: if ADD_DEVICE_IF:
out_c_file.write( "#endif\n" ) out_c_file.write( "#endif\n" )
def print_can(l): def print_can(l):
@ -775,7 +775,7 @@ def print_can(l):
out_c_file.write( """ {NC, NC, 0} out_c_file.write( """ {NC, NC, 0}
}; };
""") """)
if ADD_DEVICE_IFDEF: if ADD_DEVICE_IF:
out_c_file.write( "#endif\n" ) out_c_file.write( "#endif\n" )
def print_qspi(l): def print_qspi(l):
@ -801,7 +801,7 @@ def print_qspi(l):
out_c_file.write( """ {NC, NC, 0} out_c_file.write( """ {NC, NC, 0}
}; };
""") """)
if ADD_DEVICE_IFDEF: if ADD_DEVICE_IF:
out_c_file.write( "#endif\n" ) out_c_file.write( "#endif\n" )
def print_h_file(l, comment): def print_h_file(l, comment):