From 650963b6f821343a358caf95d064ead53a8c8ed7 Mon Sep 17 00:00:00 2001 From: "Frederic.Pillon" Date: Mon, 26 Jun 2017 11:26:15 +0200 Subject: [PATCH] Review analog pins numbering and pin functions analogRead(A0) == analogRead(0) analogWrite(A0) != analogWrite(0) == analogWrite(D0) All pins available in PinMap_ADC are available with Ax alias Fix #37 Move pin functions to pins_arduino.c to avoid duplicated code. Pin functions naming alignement. Move init() function to pins_arduino.c to avoid duplicated code and define it as weak. Minor clean of unused code. Remove usb flags for variants w/o usb. Serialx under switch.Disable by default Now, variant files only contain source which differ for each variants. Signed-off-by: Frederic Pillon --- boards.txt | 28 ++++++------- cores/arduino/Arduino.h | 2 +- cores/arduino/Tone.cpp | 4 +- cores/arduino/WInterrupts.c | 4 +- cores/arduino/pins_arduino.c | 36 +++++++++++++++++ cores/arduino/pins_arduino.h | 30 ++++++++++++++ cores/arduino/wiring_analog.c | 4 +- cores/arduino/wiring_digital.c | 6 +-- libraries/SPI/SPI.cpp | 14 +++---- libraries/Wire/Wire.cpp | 8 ++-- variants/DISCO_F407VG/PeripheralPins.c | 12 +++--- variants/DISCO_F407VG/variant.cpp | 35 +++++----------- variants/DISCO_F407VG/variant.h | 38 ++--------------- variants/DISCO_F746NG/variant.cpp | 33 ++++++--------- variants/DISCO_F746NG/variant.h | 34 +--------------- variants/NUCLEO_F030R8/PeripheralPins.c | 14 +++---- variants/NUCLEO_F030R8/variant.cpp | 28 ++++--------- variants/NUCLEO_F030R8/variant.h | 40 +++--------------- variants/NUCLEO_F091RC/PeripheralPins.c | 20 ++++----- variants/NUCLEO_F091RC/variant.cpp | 40 +++++++++--------- variants/NUCLEO_F091RC/variant.h | 39 ++---------------- variants/NUCLEO_F303RE/PeripheralPins.c | 20 ++++----- variants/NUCLEO_F303RE/variant.cpp | 40 +++++++++--------- variants/NUCLEO_F303RE/variant.h | 39 ++---------------- variants/NUCLEO_F429ZI/PeripheralPins.c | 4 +- variants/NUCLEO_F429ZI/variant.cpp | 54 ++++++++++++------------- variants/NUCLEO_F429ZI/variant.h | 50 +++++------------------ variants/NUCLEO_L053R8/PeripheralPins.c | 19 +++------ variants/NUCLEO_L053R8/variant.cpp | 37 +++++++---------- variants/NUCLEO_L053R8/variant.h | 39 ++---------------- variants/NUCLEO_L476RG/PeripheralPins.c | 16 ++++---- variants/NUCLEO_L476RG/variant.cpp | 34 +++++++--------- variants/NUCLEO_L476RG/variant.h | 39 ++---------------- 33 files changed, 311 insertions(+), 549 deletions(-) create mode 100644 cores/arduino/pins_arduino.c diff --git a/boards.txt b/boards.txt index 2fa19f883b..1fdbb1afd9 100644 --- a/boards.txt +++ b/boards.txt @@ -80,14 +80,13 @@ Nucleo_64.menu.Nucleo_64_board.NUCLEO_F091RC.upload.maximum_size=262144 Nucleo_64.menu.Nucleo_64_board.NUCLEO_F091RC.upload.maximum_data_size=32768 Nucleo_64.menu.Nucleo_64_board.NUCLEO_F091RC.build.mcu=cortex-m0 Nucleo_64.menu.Nucleo_64_board.NUCLEO_F091RC.build.f_cpu=8000000L -Nucleo_64.menu.Nucleo_64_board.NUCLEO_F091RC.build.usb_product="NUCLEO-F091RC" Nucleo_64.menu.Nucleo_64_board.NUCLEO_F091RC.build.board=NUCLEO_F091RC Nucleo_64.menu.Nucleo_64_board.NUCLEO_F091RC.build.series=STM32F0xx Nucleo_64.menu.Nucleo_64_board.NUCLEO_F091RC.build.variant=NUCLEO_F091RC Nucleo_64.menu.Nucleo_64_board.NUCLEO_F091RC.build.cmsis_lib_gcc=arm_cortexM0l_math -#To enable USB add '-DUSBCON' -#To enable HID (keyboard and mouse support) add also '-DUSBD_USE_HID_COMPOSITE' -Nucleo_64.menu.Nucleo_64_board.NUCLEO_F091RC.build.extra_flags=-DSTM32F091xC {build.usb_flags} +#To enable Serial1 (USART1 on PA10, PA9) add -DENABLE_SERIAL1 +#To enable Serial2 (USART2 on PA1, PA0) add -DENABLE_SERIAL2 +Nucleo_64.menu.Nucleo_64_board.NUCLEO_F091RC.build.extra_flags=-DSTM32F091xC # NUCLEO_F303RE board @@ -97,14 +96,13 @@ Nucleo_64.menu.Nucleo_64_board.NUCLEO_F303RE.upload.maximum_size=524288 Nucleo_64.menu.Nucleo_64_board.NUCLEO_F303RE.upload.maximum_data_size=65536 Nucleo_64.menu.Nucleo_64_board.NUCLEO_F303RE.build.mcu=cortex-m4 Nucleo_64.menu.Nucleo_64_board.NUCLEO_F303RE.build.f_cpu=8000000L -Nucleo_64.menu.Nucleo_64_board.NUCLEO_F303RE.build.usb_product="NUCLEO-F303RE" Nucleo_64.menu.Nucleo_64_board.NUCLEO_F303RE.build.board=NUCLEO_F303RE Nucleo_64.menu.Nucleo_64_board.NUCLEO_F303RE.build.series=STM32F3xx Nucleo_64.menu.Nucleo_64_board.NUCLEO_F303RE.build.variant=NUCLEO_F303RE Nucleo_64.menu.Nucleo_64_board.NUCLEO_F303RE.build.cmsis_lib_gcc=arm_cortexM4l_math -#To enable USB add '-DUSBCON' -#To enable HID (keyboard and mouse support) add also '-DUSBD_USE_HID_COMPOSITE' -Nucleo_64.menu.Nucleo_64_board.NUCLEO_F303RE.build.extra_flags=-DSTM32F303xE {build.usb_flags} +#To enable Serial1 (USART1 on PA10, PA9) add -DENABLE_SERIAL1 +#To enable Serial2 (USART2 on PA1, PA0) add -DENABLE_SERIAL2 +Nucleo_64.menu.Nucleo_64_board.NUCLEO_F303RE.build.extra_flags=-DSTM32F303xE # NUCLEO_L053R8 board @@ -114,14 +112,12 @@ Nucleo_64.menu.Nucleo_64_board.NUCLEO_L053R8.upload.maximum_size=65536 Nucleo_64.menu.Nucleo_64_board.NUCLEO_L053R8.upload.maximum_data_size=8192 Nucleo_64.menu.Nucleo_64_board.NUCLEO_L053R8.build.mcu=cortex-m0 Nucleo_64.menu.Nucleo_64_board.NUCLEO_L053R8.build.f_cpu=2000000L -Nucleo_64.menu.Nucleo_64_board.NUCLEO_L053R8.build.usb_product="NUCLEO-L053R8" Nucleo_64.menu.Nucleo_64_board.NUCLEO_L053R8.build.board=NUCLEO_L053R8 Nucleo_64.menu.Nucleo_64_board.NUCLEO_L053R8.build.series=STM32L0xx Nucleo_64.menu.Nucleo_64_board.NUCLEO_L053R8.build.variant=NUCLEO_L053R8 Nucleo_64.menu.Nucleo_64_board.NUCLEO_L053R8.build.cmsis_lib_gcc=arm_cortexM0l_math -#To enable USB add '-DUSBCON' -#To enable HID (keyboard and mouse support) add also '-DUSBD_USE_HID_COMPOSITE' -Nucleo_64.menu.Nucleo_64_board.NUCLEO_L053R8.build.extra_flags=-DSTM32L053xx -D__CORTEX_SC=0 {build.usb_flags} +#To enable Serial1 (USART1 on PA10, PA9) add -DENABLE_SERIAL1 +Nucleo_64.menu.Nucleo_64_board.NUCLEO_L053R8.build.extra_flags=-DSTM32L053xx -D__CORTEX_SC=0 # NUCLEO_L476RG board @@ -131,14 +127,12 @@ Nucleo_64.menu.Nucleo_64_board.NUCLEO_L476RG.upload.maximum_size=1048576 Nucleo_64.menu.Nucleo_64_board.NUCLEO_L476RG.upload.maximum_data_size=131072 Nucleo_64.menu.Nucleo_64_board.NUCLEO_L476RG.build.mcu=cortex-m4 Nucleo_64.menu.Nucleo_64_board.NUCLEO_L476RG.build.f_cpu=4000000L -Nucleo_64.menu.Nucleo_64_board.NUCLEO_L476RG.build.usb_product="NUCLEO-L476RG" Nucleo_64.menu.Nucleo_64_board.NUCLEO_L476RG.build.board=NUCLEO_L476RG Nucleo_64.menu.Nucleo_64_board.NUCLEO_L476RG.build.series=STM32L4xx Nucleo_64.menu.Nucleo_64_board.NUCLEO_L476RG.build.variant=NUCLEO_L476RG Nucleo_64.menu.Nucleo_64_board.NUCLEO_L476RG.build.cmsis_lib_gcc=arm_cortexM4l_math -#To enable USB add '-DUSBCON' -#To enable HID (keyboard and mouse support) add also '-DUSBD_USE_HID_COMPOSITE' -Nucleo_64.menu.Nucleo_64_board.NUCLEO_L476RG.build.extra_flags=-DSTM32L476xx {build.usb_flags} +#To enable Serial1 (USART1 on PA10, PA9) add -DENABLE_SERIAL1 +Nucleo_64.menu.Nucleo_64_board.NUCLEO_L476RG.build.extra_flags=-DSTM32L476xx Nucleo_64.menu.upload_method.MassStorageMethod=Mass Storage Nucleo_64.menu.upload_method.MassStorageMethod.upload.protocol= @@ -193,6 +187,8 @@ Disco_board.menu.Disco_board.DISCO_F746NG.build.variant=DISCO_F746NG Disco_board.menu.Disco_board.DISCO_F746NG.build.cmsis_lib_gcc=arm_cortexM7l_math #To enable USB add '-DUSBCON' #To enable HID (keyboard and mouse support) add also '-DUSBD_USE_HID_COMPOSITE' +#To enable Serial1 (USART6 on PC7, PC6) add -DENABLE_SERIAL1 +#To enable Serial2 (UART7 on PF6, PF7) add -DENABLE_SERIAL2 Disco_board.menu.Disco_board.DISCO_F746NG.build.extra_flags=-DSTM32F746xx {build.usb_flags} diff --git a/cores/arduino/Arduino.h b/cores/arduino/Arduino.h index 71f24ff8a5..d948c17879 100644 --- a/cores/arduino/Arduino.h +++ b/cores/arduino/Arduino.h @@ -72,7 +72,7 @@ extern void loop( void ) ; // Include board variant -#include "variant.h" +#include "pins_arduino.h" #include "wiring.h" #include "wiring_digital.h" diff --git a/cores/arduino/Tone.cpp b/cores/arduino/Tone.cpp index b18ff41bc6..9d587d860d 100644 --- a/cores/arduino/Tone.cpp +++ b/cores/arduino/Tone.cpp @@ -28,7 +28,7 @@ static stimer_t _timer; void tone(uint8_t _pin, unsigned int frequency, unsigned long duration) { - PinName p = digitalToPinName(_pin); + PinName p = digitalPinToPinName(_pin); if(p != NC) { if((g_lastPin == NC) || (g_lastPin == p)) { _timer.pin = p; @@ -41,7 +41,7 @@ void tone(uint8_t _pin, unsigned int frequency, unsigned long duration) void noTone(uint8_t _pin) { - PinName p = digitalToPinName(_pin); + PinName p = digitalPinToPinName(_pin); if(p != NC) { TimerPinDeinit(&_timer); digitalWrite(_pin, 0); diff --git a/cores/arduino/WInterrupts.c b/cores/arduino/WInterrupts.c index ef90317ba9..a0b5a7c6dc 100644 --- a/cores/arduino/WInterrupts.c +++ b/cores/arduino/WInterrupts.c @@ -25,7 +25,7 @@ void attachInterrupt(uint32_t pin, void (*callback)(void), uint32_t mode) { uint32_t it_mode; - PinName p = digitalToPinName(pin); + PinName p = digitalPinToPinName(pin); GPIO_TypeDef* port = set_GPIO_Port_Clock(STM_PORT(p)); if (port == NC) return; @@ -51,7 +51,7 @@ void attachInterrupt(uint32_t pin, void (*callback)(void), uint32_t mode) void detachInterrupt(uint32_t pin) { - PinName p = digitalToPinName(pin); + PinName p = digitalPinToPinName(pin); GPIO_TypeDef* port = get_GPIO_Port(STM_PORT(p)); if (port == NC) return; diff --git a/cores/arduino/pins_arduino.c b/cores/arduino/pins_arduino.c new file mode 100644 index 0000000000..936c25abea --- /dev/null +++ b/cores/arduino/pins_arduino.c @@ -0,0 +1,36 @@ +/* + Copyright (c) 2011 Arduino. All right reserved. + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + See the GNU Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA +*/ + +#include "pins_arduino.h" + +void __libc_init_array(void); + +WEAK uint32_t pinNametoDigitalPin(PinName p) +{ + uint32_t i = 0; + for(i = 0; i < NUM_DIGITAL_PINS; i++) { + if (digitalPin[i] == p) + break; + } + return i; +} + +WEAK void init( void ) +{ + hw_config_init(); +} \ No newline at end of file diff --git a/cores/arduino/pins_arduino.h b/cores/arduino/pins_arduino.h index 4e279aa7be..014ac84768 100644 --- a/cores/arduino/pins_arduino.h +++ b/cores/arduino/pins_arduino.h @@ -15,7 +15,37 @@ License along with this library; if not, write to the Free Software Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA 02110-1301 USA */ +#ifndef _PINS_ARDUINO_H_ +#define _PINS_ARDUINO_H_ + +/** + * Libc porting layers + */ +#if defined ( __GNUC__ ) /* GCC CS3 */ +# include /** RedHat Newlib minimal stub */ +#endif // API compatibility #include "variant.h" +#define NUM_DIGITAL_PINS DEND +#define NUM_ANALOG_INPUTS (AEND-A0) + +// Convert a digital pin number Dxx to a PinName Pxy +// Note: Analog pin is also a digital pin. +#define digitalPinToPinName(p) ((p < NUM_DIGITAL_PINS) ? digitalPin[p] : (STM_VALID_PINNAME(p))? (PinName)p : NC) +// Convert a PinName Pxy to a digital pin number +uint32_t pinNametoDigitalPin(PinName p); + +// Convert an analog pin number to a digital pin number +// Used by analogRead api to have A0 == 0 +#define analogInputToDigitalPin(p) ((p < NUM_ANALOG_INPUTS) ? (p+A0) : p) +// Convert an analog pin number Axx to a PinName Pxy +#define analogInputToPinName(p) (digitalPinToPinName(analogInputToDigitalPin(p))) +// All pins could manage EXTI +#define digitalPinToInterrupt(p) (p) + +#define digitalPinToPort(p) ( get_GPIO_Port(digitalPinToPinName(p)) ) +#define digitalPinToBitMask(p) ( STM_GPIO_PIN(digitalPinToPinName(p)) ) + +#endif /*_PINS_ARDUINO_H_*/ \ No newline at end of file diff --git a/cores/arduino/wiring_analog.c b/cores/arduino/wiring_analog.c index ec4436a92e..604e36ca4e 100644 --- a/cores/arduino/wiring_analog.c +++ b/cores/arduino/wiring_analog.c @@ -52,7 +52,7 @@ static inline uint32_t mapResolution(uint32_t value, uint32_t from, uint32_t to) uint32_t analogRead(uint32_t ulPin) { uint32_t value = 0; - PinName p = analogToPinName(ulPin); + PinName p = analogInputToPinName(ulPin); if(p != NC) { value = adc_read_value(p); value = mapResolution(value, ADC_RESOLUTION, _readResolution); @@ -71,7 +71,7 @@ void analogOutputInit(void) { void analogWrite(uint32_t ulPin, uint32_t ulValue) { uint8_t do_init = 0; - PinName p = analogToPinName(ulPin); + PinName p = digitalPinToPinName(ulPin); if(p != NC) { #ifdef HAL_DAC_MODULE_ENABLED if(pin_in_pinmap(p, PinMap_DAC)) { diff --git a/cores/arduino/wiring_digital.c b/cores/arduino/wiring_digital.c index 57e49cfcff..02cc6582b7 100644 --- a/cores/arduino/wiring_digital.c +++ b/cores/arduino/wiring_digital.c @@ -30,7 +30,7 @@ extern uint32_t g_anOutputPinConfigured[MAX_NB_PORT]; void pinMode( uint32_t ulPin, uint32_t ulMode ) { - PinName p = digitalToPinName(ulPin); + PinName p = digitalPinToPinName(ulPin); if(p != NC) { // If the pin that support PWM or DAC output, we need to turn it off @@ -69,7 +69,7 @@ void pinMode( uint32_t ulPin, uint32_t ulMode ) void digitalWrite( uint32_t ulPin, uint32_t ulVal ) { - PinName p = digitalToPinName(ulPin); + PinName p = digitalPinToPinName(ulPin); if(p != NC) { if(is_pin_configured(p, g_digPinConfigured)) { digital_io_write(get_GPIO_Port(STM_PORT(p)), STM_GPIO_PIN(p), ulVal); @@ -80,7 +80,7 @@ void digitalWrite( uint32_t ulPin, uint32_t ulVal ) int digitalRead( uint32_t ulPin ) { uint8_t level = 0; - PinName p = digitalToPinName(ulPin); + PinName p = digitalPinToPinName(ulPin); if(p != NC) { if(is_pin_configured(p, g_digPinConfigured)) { level = digital_io_read(get_GPIO_Port(STM_PORT(p)), STM_GPIO_PIN(p)); diff --git a/libraries/SPI/SPI.cpp b/libraries/SPI/SPI.cpp index 3cb2358d7e..656d095d6e 100644 --- a/libraries/SPI/SPI.cpp +++ b/libraries/SPI/SPI.cpp @@ -20,9 +20,9 @@ SPIClass SPI; SPIClass::SPIClass() : g_active_id(-1) { - _spi.pin_miso = digitalToPinName(MISO); - _spi.pin_mosi = digitalToPinName(MOSI); - _spi.pin_sclk = digitalToPinName(SCLK); + _spi.pin_miso = digitalPinToPinName(MISO); + _spi.pin_mosi = digitalPinToPinName(MOSI); + _spi.pin_sclk = digitalPinToPinName(SCLK); _spi.pin_ssel = NC; } @@ -31,12 +31,12 @@ ssel pin. Enable this pin disable software CS. See microcontroller documentation for the list of available SS pins. */ SPIClass::SPIClass(uint8_t mosi, uint8_t miso, uint8_t sclk, uint8_t ssel) : g_active_id(-1) { - _spi.pin_miso = digitalToPinName(miso); - _spi.pin_mosi = digitalToPinName(mosi); - _spi.pin_sclk = digitalToPinName(sclk); + _spi.pin_miso = digitalPinToPinName(miso); + _spi.pin_mosi = digitalPinToPinName(mosi); + _spi.pin_sclk = digitalPinToPinName(sclk); if(ssel != 0xFF) { - _spi.pin_ssel = digitalToPinName(ssel); + _spi.pin_ssel = digitalPinToPinName(ssel); } else { _spi.pin_ssel = NC; } diff --git a/libraries/Wire/Wire.cpp b/libraries/Wire/Wire.cpp index a93be79fa7..7ce4176763 100644 --- a/libraries/Wire/Wire.cpp +++ b/libraries/Wire/Wire.cpp @@ -45,14 +45,14 @@ void (*TwoWire::user_onReceive)(int); TwoWire::TwoWire() { - _i2c.sda = digitalToPinName(SDA); - _i2c.scl = digitalToPinName(SCL); + _i2c.sda = digitalPinToPinName(SDA); + _i2c.scl = digitalPinToPinName(SCL); } TwoWire::TwoWire(uint8_t sda, uint8_t scl) { - _i2c.sda = digitalToPinName(sda); - _i2c.scl = digitalToPinName(scl); + _i2c.sda = digitalPinToPinName(sda); + _i2c.scl = digitalPinToPinName(scl); } // Public Methods ////////////////////////////////////////////////////////////// diff --git a/variants/DISCO_F407VG/PeripheralPins.c b/variants/DISCO_F407VG/PeripheralPins.c index 03c3dffc81..9b765aef50 100644 --- a/variants/DISCO_F407VG/PeripheralPins.c +++ b/variants/DISCO_F407VG/PeripheralPins.c @@ -38,17 +38,17 @@ //*** ADC *** const PinMap PinMap_ADC[] = { - {PA0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 - User Blue button +// {PA0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0 - User Blue button // {PA0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0 - User Blue button // {PA0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0 - User Blue button {PA1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 // {PA1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 // {PA1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 // {PA2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 - {PA2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 +// {PA2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 // {PA2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2 // {PA3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 - {PA3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 +// {PA3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 // {PA3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3 // {PA4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 - I2S3_WS // {PA4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 - I2S3_WS @@ -110,7 +110,7 @@ const PinMap PinMap_I2C_SCL[] = { //*** PWM *** const PinMap PinMap_PWM[] = { - {PA0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - User Blue button +// {PA0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 - User Blue button // {PA0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1 - User Blue button {PA1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 // {PA1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 @@ -184,7 +184,7 @@ const PinMap PinMap_PWM[] = { //*** SERIAL *** const PinMap PinMap_UART_TX[] = { - {PA0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, // User Blue button +// {PA0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, // User Blue button {PA2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, // {PA9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // USB // {PB6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // Audio_SCL @@ -223,7 +223,7 @@ const PinMap PinMap_UART_RTS[] = { }; const PinMap PinMap_UART_CTS[] = { - {PA0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, // User Blue button +// {PA0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, // User Blue button // {PA11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // USB {PB13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, {PD3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, diff --git a/variants/DISCO_F407VG/variant.cpp b/variants/DISCO_F407VG/variant.cpp index 39be924228..fc038dccab 100644 --- a/variants/DISCO_F407VG/variant.cpp +++ b/variants/DISCO_F407VG/variant.cpp @@ -23,7 +23,7 @@ extern "C" { #endif // Pin number -const PinName digital_arduino[] = { +const PinName digitalPin[] = { //P1 connector Right side PC0, //D0 PC2, //D1 @@ -108,13 +108,15 @@ const PinName digital_arduino[] = { PC9, //D77 PC7, //D78 //Duplicated to have A0-A5 as F407 do not have Uno like connector - PA0, //D79/A0 - PA1, //D80/A1 - PA2, //D81/A2 - PA3, //D82/A3 - PB0, //D83/A4 - PB1 //D84/A5 -// Here we could continue to define Analog pin if we want A6,... +// and to be aligned with PinMap_ADC + PC2, //D79/A0 = D1 + PC4, //D80/A1 = D6 + PB0, //D81/A2 = D7 + PC1, //D82/A3 = D39 + PC3, //D83/A4 = D40 + PA1, //D84/A5 = D41 + PC5, //D85/A6 = D45 + PB1 //D86/A7 = D46 }; #ifdef __cplusplus @@ -141,23 +143,6 @@ void serialEventRun(void) extern "C" { #endif -void __libc_init_array(void); - -uint32_t pinNametoPinNumber(PinName p) -{ - uint32_t i = 0; - for(i = 0; i < NUM_DIGITAL_PINS; i++) { - if (digital_arduino[i] == p) - break; - } - return i; -} - -void init( void ) -{ - hw_config_init(); -} - /** * @brief System Clock Configuration * The system Clock is configured as follow : diff --git a/variants/DISCO_F407VG/variant.h b/variants/DISCO_F407VG/variant.h index b63069cb2e..a67381c5fc 100644 --- a/variants/DISCO_F407VG/variant.h +++ b/variants/DISCO_F407VG/variant.h @@ -19,16 +19,6 @@ #ifndef _VARIANT_ARDUINO_STM32_ #define _VARIANT_ARDUINO_STM32_ -/*---------------------------------------------------------------------------- - * Definitions - *----------------------------------------------------------------------------*/ - -/** Frequency of the board main oscillator */ -//#define VARIANT_MAINOSC 12000000 - -/** Master clock frequency */ -//#define VARIANT_MCK 84000000 - /*---------------------------------------------------------------------------- * Headers *----------------------------------------------------------------------------*/ @@ -39,19 +29,12 @@ extern "C"{ #endif // __cplusplus -/** - * Libc porting layers - */ -#if defined ( __GNUC__ ) /* GCC CS3 */ -# include /** RedHat Newlib minimal stub */ -#endif - /*---------------------------------------------------------------------------- * Pins *----------------------------------------------------------------------------*/ #include "PeripheralPins.h" -extern const PinName digital_arduino[]; +extern const PinName digitalPin[]; enum { D0, D1, D2, D3, D4, D5, D6, D7, D8, D9, @@ -62,31 +45,16 @@ enum { D50, D51, D52, D53, D54, D55, D56, D57, D58, D59, D60, D61, D62, D63, D64, D65, D66, D67, D68, D69, D70, D71, D72, D73, D74, D75, D76, D77, D78, D79, - D80, D81, D82, D83, D84, + D80, D81, D82, D83, D84, D85, D86, DEND }; enum { A_START_AFTER = D78, - A0, A1, A2, A3, A4, A5, + A0, A1, A2, A3, A4, A5, A6, A7, AEND }; -#define NUM_DIGITAL_PINS DEND -#define NUM_ANALOG_INPUTS (AEND - A0) - -// Convert a digital pin number Dxx to a PinName Pxy -#define digitalToPinName(p) ((p < NUM_DIGITAL_PINS) ? digital_arduino[p] : (STM_VALID_PINNAME(p))? (PinName)p : NC) -// Convert an analog pin number Axx to a PinName Pxy -#define analogToPinName(p) (digitalToPinName(p)) -// Convert an analog pin number to a digital pin number -#define analogToDigital(p) (p) -// Convert a PinName Pxy to a pin number -uint32_t pinNametoPinNumber(PinName p); - -#define digitalPinToPort(p) ( get_GPIO_Port(digitalToPinName(p)) ) -#define digitalPinToBitMask(p) ( STM_GPIO_PIN(digitalToPinName(p)) ) - //ADC resolution is 12bits #define ADC_RESOLUTION 12 #define DACC_RESOLUTION 12 diff --git a/variants/DISCO_F746NG/variant.cpp b/variants/DISCO_F746NG/variant.cpp index fa6407b8b8..fd9a80bd12 100644 --- a/variants/DISCO_F746NG/variant.cpp +++ b/variants/DISCO_F746NG/variant.cpp @@ -23,7 +23,7 @@ extern "C" { #endif // Pin number -const PinName digital_arduino[] = { +const PinName digitalPin[] = { PC7, //D0 PC6, //D1 PG6, //D2 @@ -57,23 +57,33 @@ const PinName digital_arduino[] = { * UART objects */ HardwareSerial Serial(PB7, PA9); // Connected to ST-Link +#ifdef ENABLE_SERIAL1 HardwareSerial Serial1(PC7, PC6); +#endif +#ifdef ENABLE_SERIAL2 HardwareSerial Serial2(PF6, PF7); +#endif void serialEvent() __attribute__((weak)); void serialEvent() { } - +#ifdef ENABLE_SERIAL1 void serialEvent1() __attribute__((weak)); void serialEvent1() { } - +#endif +#ifdef ENABLE_SERIAL2 void serialEvent2() __attribute__((weak)); void serialEvent2() { } +#endif void serialEventRun(void) { if (Serial.available()) serialEvent(); +#ifdef ENABLE_SERIAL1 if (Serial1.available()) serialEvent1(); +#endif +#ifdef ENABLE_SERIAL2 if (Serial2.available()) serialEvent2(); +#endif } // ---------------------------------------------------------------------------- @@ -82,23 +92,6 @@ void serialEventRun(void) extern "C" { #endif -void __libc_init_array(void); - -uint32_t pinNametoPinNumber(PinName p) -{ - uint32_t i = 0; - for(i = 0; i < NUM_DIGITAL_PINS; i++) { - if (digital_arduino[i] == p) - break; - } - return i; -} - -void init( void ) -{ - hw_config_init(); -} - /** * @brief System Clock Configuration * The system Clock is configured as follow : diff --git a/variants/DISCO_F746NG/variant.h b/variants/DISCO_F746NG/variant.h index 8835c2418d..ea48561ac6 100644 --- a/variants/DISCO_F746NG/variant.h +++ b/variants/DISCO_F746NG/variant.h @@ -19,16 +19,6 @@ #ifndef _VARIANT_ARDUINO_STM32_ #define _VARIANT_ARDUINO_STM32_ -/*---------------------------------------------------------------------------- - * Definitions - *----------------------------------------------------------------------------*/ - -/** Frequency of the board main oscillator */ -//#define VARIANT_MAINOSC 12000000 - -/** Master clock frequency */ -//#define VARIANT_MCK 84000000 - /*---------------------------------------------------------------------------- * Headers *----------------------------------------------------------------------------*/ @@ -39,19 +29,12 @@ extern "C"{ #endif // __cplusplus -/** - * Libc porting layers - */ -#if defined ( __GNUC__ ) /* GCC CS3 */ -# include /** RedHat Newlib minimal stub */ -#endif - /*---------------------------------------------------------------------------- * Pins *----------------------------------------------------------------------------*/ #include "PeripheralPins.h" -extern const PinName digital_arduino[]; +extern const PinName digitalPin[]; enum { D0, D1, D2, D3, D4, D5, D6, D7, D8, D9, @@ -66,21 +49,6 @@ enum { AEND }; -#define NUM_DIGITAL_PINS DEND -#define NUM_ANALOG_INPUTS (AEND - A0) - -// Convert a digital pin number Dxx to a PinName Pxy -#define digitalToPinName(p) ((p < NUM_DIGITAL_PINS) ? digital_arduino[p] : (STM_VALID_PINNAME(p))? (PinName)p : NC) -// Convert an analog pin number Axx to a PinName Pxy -#define analogToPinName(p) (digitalToPinName(p)) -// Convert an analog pin number to a digital pin number -#define analogToDigital(p) (p) -// Convert a PinName Pxy to a pin number -uint32_t pinNametoPinNumber(PinName p); - -#define digitalPinToPort(p) ( get_GPIO_Port(digitalToPinName(p)) ) -#define digitalPinToBitMask(p) ( STM_GPIO_PIN(digitalToPinName(p)) ) - //ADC resolution is 12bits #define ADC_RESOLUTION 12 #define DACC_RESOLUTION 12 diff --git a/variants/NUCLEO_F030R8/PeripheralPins.c b/variants/NUCLEO_F030R8/PeripheralPins.c index 6a92517a03..3a7feed478 100644 --- a/variants/NUCLEO_F030R8/PeripheralPins.c +++ b/variants/NUCLEO_F030R8/PeripheralPins.c @@ -41,14 +41,14 @@ const PinMap PinMap_ADC[] = { {PA0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC_IN0 {PA1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC_IN1 - {PA2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC_IN2 - {PA3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC_IN3 +// {PA2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC_IN2 - STLink Tx +// {PA3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC_IN3 - STLink Rx {PA4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC_IN4 - {PA5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC_IN5 +// {PA5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC_IN5 - LED {PA6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC_IN6 {PA7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC_IN7 {PB0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC_IN8 - {PB1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC_IN9 +// {PB1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC_IN9 {PC0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC_IN10 {PC1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC_IN11 {PC2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC_IN12 @@ -80,8 +80,8 @@ const PinMap PinMap_I2C_SCL[] = { //*** PWM *** const PinMap PinMap_PWM[] = { - {PA2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_TIM15, 1, 0)}, // TIM15_CH1 - {PA3, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_TIM15, 2, 0)}, // TIM15_CH2 +// {PA2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_TIM15, 1, 0)}, // TIM15_CH1 - STLink Tx +// {PA3, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_TIM15, 2, 0)}, // TIM15_CH2 - STLink Rx {PA4, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM14, 1, 0)}, // TIM14_CH1 // {PA6, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM16, 1, 0)}, // TIM16_CH1 {PA6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 1, 0)}, // TIM3_CH1 @@ -164,7 +164,7 @@ const PinMap PinMap_SPI_MISO[] = { }; const PinMap PinMap_SPI_SCLK[] = { - {PA5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, +// {PA5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, // LED {PB3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, {PB13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)}, {NC, NC, 0} diff --git a/variants/NUCLEO_F030R8/variant.cpp b/variants/NUCLEO_F030R8/variant.cpp index 180990a09f..689697b6ff 100644 --- a/variants/NUCLEO_F030R8/variant.cpp +++ b/variants/NUCLEO_F030R8/variant.cpp @@ -23,7 +23,7 @@ extern "C" { #endif // Pin number -const PinName digital_arduino[] = { +const PinName digitalPin[] = { PA3, //D0 PA2, //D1 PA10, //D2 @@ -84,6 +84,13 @@ const PinName digital_arduino[] = { PB0, //D52/A3 PC1, //D53/A4 PC0, //D54/A5 + // Duplicated pins in order to be aligned with PinMap_ADC + PA7, //D55/A6 = D11 + PA6, //D56/A7 = D12 + PC2, //D57/A8 = D29 + PC3, //D58/A9 = D30 + PC5, //D59/A10 = D36 + PC4 //D60/A11 = D46 }; #ifdef __cplusplus @@ -98,8 +105,6 @@ HardwareSerial Serial(PA3, PA2); //Connected to ST-Link HardwareSerial Serial1(PA10, PA9); #endif -// Need rework to be generic - void serialEvent() __attribute__((weak)); void serialEvent() { } #ifdef ENABLE_SERIAL1 @@ -121,23 +126,6 @@ void serialEventRun(void) extern "C" { #endif -void __libc_init_array(void); - -uint32_t pinNametoPinNumber(PinName p) -{ - uint32_t i = 0; - for(i = 0; i < NUM_DIGITAL_PINS; i++) { - if (digital_arduino[i] == p) - break; - } - return i; -} - -void init( void ) -{ - hw_config_init(); -} - /** * @brief System Clock Configuration * The system Clock is configured as follow : diff --git a/variants/NUCLEO_F030R8/variant.h b/variants/NUCLEO_F030R8/variant.h index b0295c23f9..800b0fca74 100644 --- a/variants/NUCLEO_F030R8/variant.h +++ b/variants/NUCLEO_F030R8/variant.h @@ -19,16 +19,6 @@ #ifndef _VARIANT_ARDUINO_STM32_ #define _VARIANT_ARDUINO_STM32_ -/*---------------------------------------------------------------------------- - * Definitions - *----------------------------------------------------------------------------*/ - -/** Frequency of the board main oscillator */ -//#define VARIANT_MAINOSC 12000000 - -/** Master clock frequency */ -//#define VARIANT_MCK 84000000 - /*---------------------------------------------------------------------------- * Headers *----------------------------------------------------------------------------*/ @@ -39,19 +29,12 @@ extern "C"{ #endif // __cplusplus -/** - * Libc porting layers - */ -#if defined ( __GNUC__ ) /* GCC CS3 */ -# include /** RedHat Newlib minimal stub */ -#endif - /*---------------------------------------------------------------------------- * Pins *----------------------------------------------------------------------------*/ #include "PeripheralPins.h" -extern const PinName digital_arduino[]; +extern const PinName digitalPin[]; enum { D0, D1, D2, D3, D4, D5, D6, D7, D8, D9, @@ -59,31 +42,18 @@ enum { D20, D21, D22, D23, D24, D25, D26, D27, D28, D29, D30, D31, D32, D33, D34, D35, D36, D37, D38, D39, D40, D41, D42, D43, D44, D45, D46, D47, D48, D49, - D50, D51, D52, D53, D54, + D50, D51, D52, D53, D54, D55, D56, D57, D58, D59, + D60, DEND }; enum { A_START_AFTER = D48, - A0, A1, A2, A3, A4, A5, + A0, A1, A2, A3, A4, A5, A6, A7, A8, A9, + A10, A11, AEND }; -#define NUM_DIGITAL_PINS DEND -#define NUM_ANALOG_INPUTS (AEND - A0) - -// Convert a digital pin number Dxx to a PinName Pxy -#define digitalToPinName(p) ((p < NUM_DIGITAL_PINS) ? digital_arduino[p] : (STM_VALID_PINNAME(p))? (PinName)p : NC) -// Convert an analog pin number Axx to a PinName Pxy -#define analogToPinName(p) (digitalToPinName(p)) -// Convert an analog pin number to a digital pin number -#define analogToDigital(p) (p) -// Convert a PinName Pxy to a pin number -uint32_t pinNametoPinNumber(PinName p); - -#define digitalPinToPort(p) ( get_GPIO_Port(digitalToPinName(p)) ) -#define digitalPinToBitMask(p) ( STM_GPIO_PIN(digitalToPinName(p)) ) - //ADC resolution is 12bits #define ADC_RESOLUTION 12 diff --git a/variants/NUCLEO_F091RC/PeripheralPins.c b/variants/NUCLEO_F091RC/PeripheralPins.c index 310c38d526..85a665b336 100644 --- a/variants/NUCLEO_F091RC/PeripheralPins.c +++ b/variants/NUCLEO_F091RC/PeripheralPins.c @@ -41,14 +41,14 @@ const PinMap PinMap_ADC[] = { {PA0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC_IN0 - A0 {PA1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC_IN1 - A1 - {PA2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC_IN2 - D1 - {PA3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC_IN3 - D0 +// {PA2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC_IN2 - D1 - STLink Tx +// {PA3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC_IN3 - D0 - STLink Rx {PA4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC_IN4 - A2 - {PA5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC_IN5 - D13 (LED1) +// {PA5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC_IN5 - D13 (LED1) {PA6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC_IN6 - D12 {PA7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC_IN7 - D11 {PB0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC_IN8 - A3 - {PB1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC_IN9 +// {PB1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC_IN9 {PC0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC_IN10 - A5 {PC1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC_IN11 - A4 {PC2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC_IN12 @@ -96,10 +96,10 @@ const PinMap PinMap_PWM[] = { {PA0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 1, 0)}, // TIM2_CH1 - A0 {PA1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM15, 1, 1)}, // TIM15_CH1N - A1 // {PA1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 2, 0)}, // TIM2_CH2 - A1 - {PA2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_TIM15, 1, 0)}, // TIM15_CH1 - D1 -// {PA2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 3, 0)}, // TIM2_CH3 - D1 - {PA3, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_TIM15, 2, 0)}, // TIM15_CH2 - D0 -// {PA3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 4, 0)}, // TIM2_CH4 - D0 +// {PA2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_TIM15, 1, 0)}, // TIM15_CH1 - D1 - STLink Tx +// {PA2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 3, 0)}, // TIM2_CH3 - D1 - STLink Tx +// {PA3, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_TIM15, 2, 0)}, // TIM15_CH2 - D0 - STLink Rx +// {PA3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 4, 0)}, // TIM2_CH4 - D0 - STLink Rx {PA4, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM14, 1, 0)}, // TIM14_CH1 - A2 {PA5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 1, 0)}, // TIM2_CH1 - D13 (LED1) {PA6, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_TIM16, 1, 0)}, // TIM16_CH1 - D12 @@ -115,7 +115,7 @@ const PinMap PinMap_PWM[] = { {PA15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 1, 0)}, // TIM2_CH1 // {PB0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 2, 1)}, // TIM1_CH2N {PB0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 3, 0)}, // TIM3_CH3 - A3 - {PB1, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_TIM14, 1, 0)}, // TIM14_CH1 +// {PB1, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_TIM14, 1, 0)}, // TIM14_CH1 // {PB1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM1, 3, 1)}, // TIM1_CH3N // {PB1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM3, 4, 0)}, // TIM3_CH4 {PB3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM2, 2, 0)}, // TIM2_CH2 @@ -222,7 +222,7 @@ const PinMap PinMap_SPI_MISO[] = { }; const PinMap PinMap_SPI_SCLK[] = { - {PA5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, // D13 (LED1) +// {PA5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, // D13 (LED1) {PB3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, // D3 {PB10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // D6 {PB13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)}, diff --git a/variants/NUCLEO_F091RC/variant.cpp b/variants/NUCLEO_F091RC/variant.cpp index 3c2e5f2cbb..9ea892bec5 100644 --- a/variants/NUCLEO_F091RC/variant.cpp +++ b/variants/NUCLEO_F091RC/variant.cpp @@ -23,7 +23,7 @@ extern "C" { #endif // Pin number -const PinName digital_arduino[] = { +const PinName digitalPin[] = { PA3, //D0 PA2, //D1 PA10, //D2 @@ -81,6 +81,13 @@ const PinName digital_arduino[] = { PB0, //D49/A3 PC1, //D50/A4 PC0, //D51/A5 + // Duplicated pins in order to be aligned with PinMap_ADC + PA7, //D52/A6 = D11 + PA6, //D53/A7 = D12 + PC2, //D54/A8 = D28 + PC3, //D55/A9 = D29 + PC5, //D56/A10 = D35 + PC4 //D57/A11 = D45 }; #ifdef __cplusplus @@ -91,23 +98,33 @@ const PinName digital_arduino[] = { * UART objects */ HardwareSerial Serial(PA3, PA2); //Connected to ST-Link +#ifdef ENABLE_SERIAL1 HardwareSerial Serial1(PA10, PA9); +#endif +#ifdef ENABLE_SERIAL2 HardwareSerial Serial2(PA1, PA0); - -// Need rework to be generic +#endif void serialEvent() __attribute__((weak)); void serialEvent() { } +#ifdef ENABLE_SERIAL1 void serialEvent1() __attribute__((weak)); void serialEvent1() { } +#endif +#ifdef ENABLE_SERIAL2 void serialEvent2() __attribute__((weak)); void serialEvent2() { } +#endif void serialEventRun(void) { if (Serial.available()) serialEvent(); +#ifdef ENABLE_SERIAL1 if (Serial1.available()) serialEvent1(); +#endif +#ifdef ENABLE_SERIAL2 if (Serial2.available()) serialEvent2(); +#endif } // ---------------------------------------------------------------------------- @@ -116,23 +133,6 @@ void serialEventRun(void) extern "C" { #endif -void __libc_init_array(void); - -uint32_t pinNametoPinNumber(PinName p) -{ - uint32_t i = 0; - for(i = 0; i < NUM_DIGITAL_PINS; i++) { - if (digital_arduino[i] == p) - break; - } - return i; -} - -void init( void ) -{ - hw_config_init(); -} - /** * @brief System Clock Configuration * @param None diff --git a/variants/NUCLEO_F091RC/variant.h b/variants/NUCLEO_F091RC/variant.h index 1a2af40eae..37d2b0df8b 100644 --- a/variants/NUCLEO_F091RC/variant.h +++ b/variants/NUCLEO_F091RC/variant.h @@ -19,16 +19,6 @@ #ifndef _VARIANT_ARDUINO_STM32_ #define _VARIANT_ARDUINO_STM32_ -/*---------------------------------------------------------------------------- - * Definitions - *----------------------------------------------------------------------------*/ - -/** Frequency of the board main oscillator */ -//#define VARIANT_MAINOSC 12000000 - -/** Master clock frequency */ -//#define VARIANT_MCK 84000000 - /*---------------------------------------------------------------------------- * Headers *----------------------------------------------------------------------------*/ @@ -39,19 +29,12 @@ extern "C"{ #endif // __cplusplus -/** - * Libc porting layers - */ -#if defined ( __GNUC__ ) /* GCC CS3 */ -# include /** RedHat Newlib minimal stub */ -#endif - /*---------------------------------------------------------------------------- * Pins *----------------------------------------------------------------------------*/ #include "PeripheralPins.h" -extern const PinName digital_arduino[]; +extern const PinName digitalPin[]; enum { D0, D1, D2, D3, D4, D5, D6, D7, D8, D9, @@ -59,31 +42,17 @@ enum { D20, D21, D22, D23, D24, D25, D26, D27, D28, D29, D30, D31, D32, D33, D34, D35, D36, D37, D38, D39, D40, D41, D42, D43, D44, D45, D46, D47, D48, D49, - D50, D51, + D50, D51, D52, D53, D54, D55, D56, D57, DEND }; enum { A_START_AFTER = D45, - A0, A1, A2, A3, A4, A5, + A0, A1, A2, A3, A4, A5, A6, A7, A8, A9, + A10, A11, AEND }; -#define NUM_DIGITAL_PINS DEND -#define NUM_ANALOG_INPUTS (AEND - A0) - -// Convert a digital pin number Dxx to a PinName Pxy -#define digitalToPinName(p) ((p < NUM_DIGITAL_PINS) ? digital_arduino[p] : (STM_VALID_PINNAME(p))? (PinName)p : NC) -// Convert an analog pin number Axx to a PinName Pxy -#define analogToPinName(p) (digitalToPinName(p)) -// Convert an analog pin number to a digital pin number -#define analogToDigital(p) (p) -// Convert a PinName Pxy to a pin number -uint32_t pinNametoPinNumber(PinName p); - -#define digitalPinToPort(p) ( get_GPIO_Port(digitalToPinName(p)) ) -#define digitalPinToBitMask(p) ( STM_GPIO_PIN(digitalToPinName(p)) ) - //ADC resolution is 12bits #define ADC_RESOLUTION 12 #define DACC_RESOLUTION 12 diff --git a/variants/NUCLEO_F303RE/PeripheralPins.c b/variants/NUCLEO_F303RE/PeripheralPins.c index 8bf9fc9c20..3cc63e50b5 100644 --- a/variants/NUCLEO_F303RE/PeripheralPins.c +++ b/variants/NUCLEO_F303RE/PeripheralPins.c @@ -41,14 +41,14 @@ const PinMap PinMap_ADC[] = { {PA0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 - A0 {PA1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2 - A1 - {PA2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 - {PA3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 +// {PA2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3 - STLink Tx +// {PA3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4 - STLink Rx {PA4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 - A2 - {PA5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 - LED1 +// {PA5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2 - LED1 {PA6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3 {PA7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4 {PB0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12 - {PB1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 +// {PB1, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1 {PB2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 {PB11, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 // {PB11, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 @@ -106,10 +106,10 @@ const PinMap PinMap_PWM[] = { // {PA0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 {PA1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM15, 1, 1)}, // TIM15_CH1N // {PA1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - {PA2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM15, 1, 0)}, // TIM15_CH1 -// {PA2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - {PA3, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM15, 2, 0)}, // TIM15_CH2 -// {PA3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 +// {PA2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM15, 1, 0)}, // TIM15_CH1 - STLink Tx +// {PA2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - STLink Tx +// {PA3, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM15, 2, 0)}, // TIM15_CH2 - STLink Rx +// {PA3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4 - STLink Rx {PA4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 // {PA5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1 {PA6, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM16, 1, 0)}, // TIM16_CH1 @@ -137,7 +137,7 @@ const PinMap PinMap_PWM[] = { {PB0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_TIM1, 2, 1)}, // TIM1_CH2N // {PB0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 // {PB0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM8, 2, 1)}, // TIM8_CH2N - {PB1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_TIM1, 3, 1)}, // TIM1_CH3N +// {PB1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_TIM1, 3, 1)}, // TIM1_CH3N // {PB1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 // {PB1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM8, 3, 1)}, // TIM8_CH3N // {PB3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 @@ -258,7 +258,7 @@ const PinMap PinMap_SPI_MISO[] = { }; const PinMap PinMap_SPI_SCLK[] = { - {PA5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // LED1 +// {PA5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // LED1 // {PB3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, {PB3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, {PB13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, diff --git a/variants/NUCLEO_F303RE/variant.cpp b/variants/NUCLEO_F303RE/variant.cpp index caa590829d..88d23c3476 100644 --- a/variants/NUCLEO_F303RE/variant.cpp +++ b/variants/NUCLEO_F303RE/variant.cpp @@ -23,7 +23,7 @@ extern "C" { #endif // Pin number -const PinName digital_arduino[] = { +const PinName digitalPin[] = { PA3, //D0 PA2, //D1 PA10, //D2 @@ -81,6 +81,13 @@ const PinName digital_arduino[] = { PB0, //D49/A3 PC1, //D50/A4 PC0, //D51/A5 + // Duplicated pins in order to be aligned with PinMap_ADC + PA7, //D52/A6 = D11 + PA6, //D53/A7 = D12 + PC2, //D54/A8 = D28 + PC3, //D55/A9 = D29 + PC5, //D56/A10 = D35 + PC4 //D57/A11 = D45 }; #ifdef __cplusplus @@ -91,23 +98,33 @@ const PinName digital_arduino[] = { * UART objects */ HardwareSerial Serial(PA3, PA2); //Connected to ST-Link +#ifdef ENABLE_SERIAL1 HardwareSerial Serial1(PA10, PA9); +#endif +#ifdef ENABLE_SERIAL2 HardwareSerial Serial2(PA1, PA0); - -// Need rework to be generic +#endif void serialEvent() __attribute__((weak)); void serialEvent() { } +#ifdef ENABLE_SERIAL1 void serialEvent1() __attribute__((weak)); void serialEvent1() { } +#endif +#ifdef ENABLE_SERIAL2 void serialEvent2() __attribute__((weak)); void serialEvent2() { } +#endif void serialEventRun(void) { if (Serial.available()) serialEvent(); +#ifdef ENABLE_SERIAL1 if (Serial1.available()) serialEvent1(); +#endif +#ifdef ENABLE_SERIAL2 if (Serial2.available()) serialEvent2(); +#endif } // ---------------------------------------------------------------------------- @@ -116,23 +133,6 @@ void serialEventRun(void) extern "C" { #endif -void __libc_init_array(void); - -uint32_t pinNametoPinNumber(PinName p) -{ - uint32_t i = 0; - for(i = 0; i < NUM_DIGITAL_PINS; i++) { - if (digital_arduino[i] == p) - break; - } - return i; -} - -void init( void ) -{ - hw_config_init(); -} - /** * @brief System Clock Configuration * @param None diff --git a/variants/NUCLEO_F303RE/variant.h b/variants/NUCLEO_F303RE/variant.h index 9675585bc1..ca768bffec 100644 --- a/variants/NUCLEO_F303RE/variant.h +++ b/variants/NUCLEO_F303RE/variant.h @@ -19,16 +19,6 @@ #ifndef _VARIANT_ARDUINO_STM32_ #define _VARIANT_ARDUINO_STM32_ -/*---------------------------------------------------------------------------- - * Definitions - *----------------------------------------------------------------------------*/ - -/** Frequency of the board main oscillator */ -//#define VARIANT_MAINOSC 12000000 - -/** Master clock frequency */ -//#define VARIANT_MCK 84000000 - /*---------------------------------------------------------------------------- * Headers *----------------------------------------------------------------------------*/ @@ -39,19 +29,12 @@ extern "C"{ #endif // __cplusplus -/** - * Libc porting layers - */ -#if defined ( __GNUC__ ) /* GCC CS3 */ -# include /** RedHat Newlib minimal stub */ -#endif - /*---------------------------------------------------------------------------- * Pins *----------------------------------------------------------------------------*/ #include "PeripheralPins.h" -extern const PinName digital_arduino[]; +extern const PinName digitalPin[]; enum { D0, D1, D2, D3, D4, D5, D6, D7, D8, D9, @@ -59,31 +42,17 @@ enum { D20, D21, D22, D23, D24, D25, D26, D27, D28, D29, D30, D31, D32, D33, D34, D35, D36, D37, D38, D39, D40, D41, D42, D43, D44, D45, D46, D47, D48, D49, - D50, D51, + D50, D51, D52, D53, D54, D55, D56, D57, DEND }; enum { A_START_AFTER = D45, - A0, A1, A2, A3, A4, A5, + A0, A1, A2, A3, A4, A5, A6, A7, A8, A9, + A10, A11, AEND }; -#define NUM_DIGITAL_PINS DEND -#define NUM_ANALOG_INPUTS (AEND - A0) - -// Convert a digital pin number Dxx to a PinName Pxy -#define digitalToPinName(p) ((p < NUM_DIGITAL_PINS) ? digital_arduino[p] : (STM_VALID_PINNAME(p))? (PinName)p : NC) -// Convert an analog pin number Axx to a PinName Pxy -#define analogToPinName(p) (digitalToPinName(p)) -// Convert an analog pin number to a digital pin number -#define analogToDigital(p) (p) -// Convert a PinName Pxy to a pin number -uint32_t pinNametoPinNumber(PinName p); - -#define digitalPinToPort(p) ( get_GPIO_Port(digitalToPinName(p)) ) -#define digitalPinToBitMask(p) ( STM_GPIO_PIN(digitalToPinName(p)) ) - //ADC resolution is 12bits #define ADC_RESOLUTION 12 #define DACC_RESOLUTION 12 diff --git a/variants/NUCLEO_F429ZI/PeripheralPins.c b/variants/NUCLEO_F429ZI/PeripheralPins.c index 2900a65f3e..15848a32be 100644 --- a/variants/NUCLEO_F429ZI/PeripheralPins.c +++ b/variants/NUCLEO_F429ZI/PeripheralPins.c @@ -74,9 +74,9 @@ const PinMap PinMap_ADC[] = { {PC3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13 - A2 // {PC3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13 - A2 // {PC3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13 - A2 - {PC4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 - ETH RMII RXD0 (when JP7 ON) +// {PC4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14 - ETH RMII RXD0 (when JP7 ON) // {PC4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14 - ETH RMII RXD0 (when JP7 ON) - {PC5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 - ETH RMII RXD1 (when JP7 ON) +// {PC5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 - ETH RMII RXD1 (when JP7 ON) // {PC5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 - ETH RMII RXD1 (when JP7 ON) {PF3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9 - A3 {PF4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14 diff --git a/variants/NUCLEO_F429ZI/variant.cpp b/variants/NUCLEO_F429ZI/variant.cpp index 2c9018deb1..92f1c87a0e 100644 --- a/variants/NUCLEO_F429ZI/variant.cpp +++ b/variants/NUCLEO_F429ZI/variant.cpp @@ -25,7 +25,7 @@ extern "C" { // Pin number // Match Table 17. NUCLEO-F429ZI pin assignments // from UM1974 STM32 Nucleo-144 board -const PinName digital_arduino[] = { +const PinName digitalPin[] = { PG9, //D0 PG14, //D1 PF15, //D2 @@ -59,7 +59,7 @@ const PinName digital_arduino[] = { PD11, //D30 PE2, //D31 PA0, //D32 - PB0, //D33 + PB0, //D33 - LED_GREEN PE0, //D34 PB11, //D35 PB10, //D36 @@ -99,15 +99,30 @@ const PinName digital_arduino[] = { PF2, //D70 PA7, //D71 NC, //D72 - PA3, //D73/A0 - PC0, //D74/A1 - PC3, //D75/A2 - PF3, //D76/A3 - PF5, //D77/A4 - PF10, //D78/A5 - PB7, //D79 - PB14, //D80 - PC13 //D81 + PB7, //D73 - LED_BLUE + PB14, //D74 - LED_RED + PC13, //D75 - USER_BTN + PD9, //D76 - Serial Rx + PD8, //D77 - Serial Tx + PA3, //D78/A0 + PC0, //D79/A1 + PC3, //D80/A2 + PF3, //D81/A3 + PF5, //D82/A4 + PF10, //D83/A5 + PB1, //D84/A6 + PC2, //D85/A7 + PF4, //D86/A8 + PF6, //D87/A9 + // Duplicated pins in order to be aligned with PinMap_ADC + PA7, //D88/A10 = D11 + PA6, //D89/A11 = D12 + PA5, //D90/A12 = D13 + PA4, //D91/A13 = D24 + PA0, //D92/A14 = D32 + PF8, //D93/A15 = D61 + PF7, //D94/A16 = D62 + PF9 //D95/A17 = D63 }; #ifdef __cplusplus @@ -143,23 +158,6 @@ void serialEventRun(void) extern "C" { #endif -void __libc_init_array(void); - -uint32_t pinNametoPinNumber(PinName p) -{ - uint32_t i = 0; - for(i = 0; i < NUM_DIGITAL_PINS; i++) { - if (digital_arduino[i] == p) - break; - } - return i; -} - -void init( void ) -{ - hw_config_init(); -} - /** * @brief System Clock Configuration * The system Clock is configured as follow : diff --git a/variants/NUCLEO_F429ZI/variant.h b/variants/NUCLEO_F429ZI/variant.h index 437ac6f428..d0a8f23777 100644 --- a/variants/NUCLEO_F429ZI/variant.h +++ b/variants/NUCLEO_F429ZI/variant.h @@ -19,16 +19,6 @@ #ifndef _VARIANT_ARDUINO_STM32_ #define _VARIANT_ARDUINO_STM32_ -/*---------------------------------------------------------------------------- - * Definitions - *----------------------------------------------------------------------------*/ - -/** Frequency of the board main oscillator */ -//#define VARIANT_MAINOSC 12000000 - -/** Master clock frequency */ -//#define VARIANT_MCK 84000000 - /*---------------------------------------------------------------------------- * Headers *----------------------------------------------------------------------------*/ @@ -39,19 +29,12 @@ extern "C"{ #endif // __cplusplus -/** - * Libc porting layers - */ -#if defined ( __GNUC__ ) /* GCC CS3 */ -# include /** RedHat Newlib minimal stub */ -#endif - /*---------------------------------------------------------------------------- * Pins *----------------------------------------------------------------------------*/ #include "PeripheralPins.h" -extern const PinName digital_arduino[]; +extern const PinName digitalPin[]; enum { D0, D1, D2, D3, D4, D5, D6, D7, D8, D9, @@ -62,31 +45,18 @@ enum { D50, D51, D52, D53, D54, D55, D56, D57, D58, D59, D60, D61, D62, D63, D64, D65, D66, D67, D68, D69, D70, D71, D72, D73, D74, D75, D76, D77, D78, D79, - D80, D81, + D80, D81, D82, D83, D84, D85, D86, D87, D88, D89, + D90, D91, D92, D93, D94, D95, DEND }; enum { - A_START_AFTER = D72, - A0, A1, A2, A3, A4, A5, + A_START_AFTER = D77, + A0, A1, A2, A3, A4, A5, A6, A7, A8, A9, + A10, A11, A12, A13, A14, A15, A16, A17, AEND }; -#define NUM_DIGITAL_PINS DEND -#define NUM_ANALOG_INPUTS (AEND - A0) - -// Convert a digital pin number Dxx to a PinName Pxy -#define digitalToPinName(p) ((p < NUM_DIGITAL_PINS) ? digital_arduino[p] : (STM_VALID_PINNAME(p))? (PinName)p : NC) -// Convert an analog pin number Axx to a PinName Pxy -#define analogToPinName(p) (digitalToPinName(p)) -// Convert an analog pin number to a digital pin number -#define analogToDigital(p) (p) -// Convert a PinName Pxy to a pin number -uint32_t pinNametoPinNumber(PinName p); - -#define digitalPinToPort(p) ( get_GPIO_Port(digitalToPinName(p)) ) -#define digitalPinToBitMask(p) ( STM_GPIO_PIN(digitalToPinName(p)) ) - //ADC resolution is 12bits #define ADC_RESOLUTION 12 #define DACC_RESOLUTION 12 @@ -99,11 +69,11 @@ uint32_t pinNametoPinNumber(PinName p); //On-board LED pin number #define LED_BUILTIN 33 #define LED_GREEN LED_BUILTIN -#define LED_BLUE 79 -#define LED_RED 80 +#define LED_BLUE 73 +#define LED_RED 74 //On-board user button -#define USER_BTN 81 +#define USER_BTN 75 //SPI definitions @@ -146,6 +116,8 @@ uint32_t pinNametoPinNumber(PinName p); //Enable Firmata #define STM32 1 + + #ifdef __cplusplus } // extern "C" #endif diff --git a/variants/NUCLEO_L053R8/PeripheralPins.c b/variants/NUCLEO_L053R8/PeripheralPins.c index 9e1326cc96..5985e4ed42 100644 --- a/variants/NUCLEO_L053R8/PeripheralPins.c +++ b/variants/NUCLEO_L053R8/PeripheralPins.c @@ -41,14 +41,14 @@ const PinMap PinMap_ADC[] = { {PA0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC_IN0 {PA1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC_IN1 - {PA2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC_IN2 - {PA3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC_IN3 +// {PA2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC_IN2 - STLink Tx +// {PA3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC_IN3 - STLink Rx {PA4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC_IN4 - {PA5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC_IN5 +// {PA5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC_IN5 - LED {PA6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC_IN6 {PA7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC_IN7 {PB0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC_IN8 - {PB1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC_IN9 +// {PB1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC_IN9 {PC0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC_IN10 {PC1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC_IN11 {PC2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC_IN12 @@ -171,7 +171,7 @@ const PinMap PinMap_SPI_MISO[] = { }; const PinMap PinMap_SPI_SCLK[] = { - {PA5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, +// {PA5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, // LED {PB3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI1)}, {PB10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, {PB13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF0_SPI2)}, @@ -187,11 +187,4 @@ const PinMap PinMap_SPI_SSEL[] = { }; //*** CAN *** - -const PinMap PinMap_CAN_RD[] = { - {NC, NC, 0} -}; - -const PinMap PinMap_CAN_TD[] = { - {NC, NC, 0} -}; +// NO CAN \ No newline at end of file diff --git a/variants/NUCLEO_L053R8/variant.cpp b/variants/NUCLEO_L053R8/variant.cpp index 022ba5d28b..051a937674 100644 --- a/variants/NUCLEO_L053R8/variant.cpp +++ b/variants/NUCLEO_L053R8/variant.cpp @@ -23,7 +23,7 @@ extern "C" { #endif // Pin number -const PinName digital_arduino[] = { +const PinName digitalPin[] = { PA3, //D0 PA2, //D1 PA10, //D2 @@ -54,8 +54,7 @@ const PinName digital_arduino[] = { PC15, //D25 PH0, //D26 PH1, //D27 - PC2, //D28// Match Table 17. NUCLEO-F429ZI pin assignments -// from UM1974 STM32 Nucleo-144 board + PC2, //D28 PC3, //D29 // CN7 Right Side PC11, //D30 @@ -82,6 +81,13 @@ const PinName digital_arduino[] = { PB0, //D49/A3 PC1, //D50/A4 PC0, //D51/A5 + // Duplicated pins in order to be aligned with PinMap_ADC + PA7, //D52/A6 = D11 + PA6, //D53/A7 = D12 + PC2, //D54/A8 = D28 + PC3, //D55/A9 = D29 + PC5, //D56/A10 = D35 + PC4 //D57/A11 = D45 }; #ifdef __cplusplus @@ -92,19 +98,23 @@ const PinName digital_arduino[] = { * UART objects */ HardwareSerial Serial(PA3, PA2); //Connected to ST-Link +#ifdef ENABLE_SERIAL1 HardwareSerial Serial1(PA10, PA9); - -// Need rework to be generic +#endif void serialEvent() __attribute__((weak)); void serialEvent() { } +#ifdef ENABLE_SERIAL1 void serialEvent1() __attribute__((weak)); void serialEvent1() { } +#endif void serialEventRun(void) { if (Serial.available()) serialEvent(); +#ifdef ENABLE_SERIAL1 if (Serial1.available()) serialEvent1(); +#endif } // ---------------------------------------------------------------------------- @@ -113,23 +123,6 @@ void serialEventRun(void) extern "C" { #endif -void __libc_init_array(void); - -uint32_t pinNametoPinNumber(PinName p) -{ - uint32_t i = 0; - for(i = 0; i < NUM_DIGITAL_PINS; i++) { - if (digital_arduino[i] == p) - break; - } - return i; -} - -void init( void ) -{ - hw_config_init(); -} - /** * @brief System Clock Configuration * @param None diff --git a/variants/NUCLEO_L053R8/variant.h b/variants/NUCLEO_L053R8/variant.h index 86b073b2e5..c4f38381a6 100644 --- a/variants/NUCLEO_L053R8/variant.h +++ b/variants/NUCLEO_L053R8/variant.h @@ -19,16 +19,6 @@ #ifndef _VARIANT_ARDUINO_STM32_ #define _VARIANT_ARDUINO_STM32_ -/*---------------------------------------------------------------------------- - * Definitions - *----------------------------------------------------------------------------*/ - -/** Frequency of the board main oscillator */ -//#define VARIANT_MAINOSC 12000000 - -/** Master clock frequency */ -//#define VARIANT_MCK 84000000 - /*---------------------------------------------------------------------------- * Headers *----------------------------------------------------------------------------*/ @@ -39,19 +29,12 @@ extern "C"{ #endif // __cplusplus -/** - * Libc porting layers - */ -#if defined ( __GNUC__ ) /* GCC CS3 */ -# include /** RedHat Newlib minimal stub */ -#endif - /*---------------------------------------------------------------------------- * Pins *----------------------------------------------------------------------------*/ #include "PeripheralPins.h" -extern const PinName digital_arduino[]; +extern const PinName digitalPin[]; enum { D0, D1, D2, D3, D4, D5, D6, D7, D8, D9, @@ -59,31 +42,17 @@ enum { D20, D21, D22, D23, D24, D25, D26, D27, D28, D29, D30, D31, D32, D33, D34, D35, D36, D37, D38, D39, D40, D41, D42, D43, D44, D45, D46, D47, D48, D49, - D50, D51, + D50, D51, D52, D53, D54, D55, D56, D57, DEND }; enum { A_START_AFTER = D45, - A0, A1, A2, A3, A4, A5, + A0, A1, A2, A3, A4, A5, A6, A7, A8, A9, + A10, A11, AEND }; -#define NUM_DIGITAL_PINS DEND -#define NUM_ANALOG_INPUTS (AEND - A0) - -// Convert a digital pin number Dxx to a PinName Pxy -#define digitalToPinName(p) ((p < NUM_DIGITAL_PINS) ? digital_arduino[p] : (STM_VALID_PINNAME(p))? (PinName)p : NC) -// Convert an analog pin number Axx to a PinName Pxy -#define analogToPinName(p) (digitalToPinName(p)) -// Convert an analog pin number to a digital pin number -#define analogToDigital(p) (p) -// Convert a PinName Pxy to a pin number -uint32_t pinNametoPinNumber(PinName p); - -#define digitalPinToPort(p) ( get_GPIO_Port(digitalToPinName(p)) ) -#define digitalPinToBitMask(p) ( STM_GPIO_PIN(digitalToPinName(p)) ) - //ADC resolution is 12bits #define ADC_RESOLUTION 12 #define DACC_RESOLUTION 12 diff --git a/variants/NUCLEO_L476RG/PeripheralPins.c b/variants/NUCLEO_L476RG/PeripheralPins.c index e62af11d75..2baf59e970 100644 --- a/variants/NUCLEO_L476RG/PeripheralPins.c +++ b/variants/NUCLEO_L476RG/PeripheralPins.c @@ -43,13 +43,13 @@ const PinMap PinMap_ADC[] = { // {PA0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5 {PA1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6 // {PA1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6 - {PA2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 -// {PA2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 - {PA3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 -// {PA3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 +// {PA2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7 - STLink Tx +// {PA2, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7 - STLink Tx +// {PA3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8 - STLink Rx +// {PA3, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8 - STLink Rx {PA4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9 // {PA4, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9 - {PA5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 +// {PA5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10 - LED // {PA5, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10 {PA6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11 // {PA6, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11 @@ -57,7 +57,7 @@ const PinMap PinMap_ADC[] = { // {PA7, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12 {PB0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15 // {PB0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15 - {PB1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 16, 0)}, // ADC1_IN16 +// {PB1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 16, 0)}, // ADC1_IN16 // {PB1, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 16, 0)}, // ADC2_IN16 {PC0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1 // {PC0, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1 @@ -137,7 +137,7 @@ const PinMap PinMap_PWM[] = { {PB0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 // {PB0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N // {PB1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N - {PB1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 +// {PB1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4 // {PB1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N {PB3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 {PB4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1 @@ -251,7 +251,7 @@ const PinMap PinMap_SPI_MISO[] = { }; const PinMap PinMap_SPI_SCLK[] = { - {PA5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, +// {PA5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // LED {PB3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // {PB3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, {PB10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, diff --git a/variants/NUCLEO_L476RG/variant.cpp b/variants/NUCLEO_L476RG/variant.cpp index 286a257a79..5b3d5b477c 100644 --- a/variants/NUCLEO_L476RG/variant.cpp +++ b/variants/NUCLEO_L476RG/variant.cpp @@ -23,7 +23,7 @@ extern "C" { #endif // Pin number -const PinName digital_arduino[] = { +const PinName digitalPin[] = { PA3, //D0 PA2, //D1 PA10, //D2 @@ -37,7 +37,7 @@ const PinName digital_arduino[] = { PB6, //D10 PA7, //D11 PA6, //D12 - PA5, //D13 + PA5, //D13 - LED PB9, //D14 PB8, //D15 // ST Morpho @@ -81,6 +81,13 @@ const PinName digital_arduino[] = { PB0, //D49/A3 PC1, //D50/A4 PC0, //D51/A5 + // Duplicated pins in order to be aligned with PinMap_ADC + PA7, //D52/A6 = D11 + PA6, //D53/A7 = D12 + PC2, //D54/A8 = D28 + PC3, //D55/A9 = D29 + PC5, //D56/A10 = D35 + PC4 //D57/A11 = D45 }; #ifdef __cplusplus @@ -91,17 +98,23 @@ const PinName digital_arduino[] = { * UART objects */ HardwareSerial Serial(PA3, PA2); //Connected to ST-Link +#ifdef ENABLE_SERIAL1 HardwareSerial Serial1(PA10, PA9); +#endif void serialEvent() __attribute__((weak)); void serialEvent() { } +#ifdef ENABLE_SERIAL1 void serialEvent1() __attribute__((weak)); void serialEvent1() { } +#endif void serialEventRun(void) { if (Serial.available()) serialEvent(); +#ifdef ENABLE_SERIAL1 if (Serial1.available()) serialEvent1(); +#endif } // ---------------------------------------------------------------------------- @@ -110,23 +123,6 @@ void serialEventRun(void) extern "C" { #endif -void __libc_init_array(void); - -uint32_t pinNametoPinNumber(PinName p) -{ - uint32_t i = 0; - for(i = 0; i < NUM_DIGITAL_PINS; i++) { - if (digital_arduino[i] == p) - break; - } - return i; -} - -void init( void ) -{ - hw_config_init(); -} - /** * @brief System Clock Configuration * The system Clock is configured as follows : diff --git a/variants/NUCLEO_L476RG/variant.h b/variants/NUCLEO_L476RG/variant.h index 03f58f4d35..ed207ed980 100644 --- a/variants/NUCLEO_L476RG/variant.h +++ b/variants/NUCLEO_L476RG/variant.h @@ -19,16 +19,6 @@ #ifndef _VARIANT_ARDUINO_STM32_ #define _VARIANT_ARDUINO_STM32_ -/*---------------------------------------------------------------------------- - * Definitions - *----------------------------------------------------------------------------*/ - -/** Frequency of the board main oscillator */ -//#define VARIANT_MAINOSC 12000000 - -/** Master clock frequency */ -//#define VARIANT_MCK 84000000 - /*---------------------------------------------------------------------------- * Headers *----------------------------------------------------------------------------*/ @@ -39,19 +29,12 @@ extern "C"{ #endif // __cplusplus -/** - * Libc porting layers - */ -#if defined ( __GNUC__ ) /* GCC CS3 */ -# include /** RedHat Newlib minimal stub */ -#endif - /*---------------------------------------------------------------------------- * Pins *----------------------------------------------------------------------------*/ #include "PeripheralPins.h" -extern const PinName digital_arduino[]; +extern const PinName digitalPin[]; enum { D0, D1, D2, D3, D4, D5, D6, D7, D8, D9, @@ -59,31 +42,17 @@ enum { D20, D21, D22, D23, D24, D25, D26, D27, D28, D29, D30, D31, D32, D33, D34, D35, D36, D37, D38, D39, D40, D41, D42, D43, D44, D45, D46, D47, D48, D49, - D50, D51, + D50, D51, D52, D53, D54, D55, D56, D57, DEND }; enum { A_START_AFTER = D45, - A0, A1, A2, A3, A4, A5, + A0, A1, A2, A3, A4, A5, A6, A7, A8, A9, + A10, A11, AEND }; -#define NUM_DIGITAL_PINS DEND -#define NUM_ANALOG_INPUTS (AEND - A0) - -// Convert a digital pin number Dxx to a PinName Pxy -#define digitalToPinName(p) ((p < NUM_DIGITAL_PINS) ? digital_arduino[p] : (STM_VALID_PINNAME(p))? (PinName)p : NC) -// Convert an analog pin number Axx to a PinName Pxy -#define analogToPinName(p) (digitalToPinName(p)) -// Convert an analog pin number to a digital pin number -#define analogToDigital(p) (p) -// Convert a PinName Pxy to a pin number -uint32_t pinNametoPinNumber(PinName p); - -#define digitalPinToPort(p) ( get_GPIO_Port(digitalToPinName(p)) ) -#define digitalPinToBitMask(p) ( STM_GPIO_PIN(digitalToPinName(p)) ) - //ADC resolution is 12bits #define ADC_RESOLUTION 12 #define DACC_RESOLUTION 12