diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/PeripheralPins.h b/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/PeripheralPins.h deleted file mode 100644 index 383d022e69..0000000000 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/PeripheralPins.h +++ /dev/null @@ -1,62 +0,0 @@ -/* mbed Microcontroller Library - ******************************************************************************* - * Copyright (c) 2014, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - ******************************************************************************* - */ - -#ifndef MBED_PERIPHERALPINS_H -#define MBED_PERIPHERALPINS_H - -#include "pinmap.h" -#include "PeripheralNames.h" - -//*** ADC *** - -extern const PinMap PinMap_ADC[]; - -//*** I2C *** - -extern const PinMap PinMap_I2C_SDA[]; -extern const PinMap PinMap_I2C_SCL[]; - -//*** PWM *** - -extern const PinMap PinMap_PWM[]; - -//*** SERIAL *** - -extern const PinMap PinMap_UART_TX[]; -extern const PinMap PinMap_UART_RX[]; - -//*** SPI *** - -extern const PinMap PinMap_SPI_MOSI[]; -extern const PinMap PinMap_SPI_MISO[]; -extern const PinMap PinMap_SPI_SCLK[]; -extern const PinMap PinMap_SPI_SSEL[]; - -#endif diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/analogin_api.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/analogin_api.c deleted file mode 100644 index 41a0f273e8..0000000000 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/analogin_api.c +++ /dev/null @@ -1,175 +0,0 @@ -/* mbed Microcontroller Library - * Copyright (c) 2014, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#include "mbed_assert.h" -#include "analogin_api.h" - -#if DEVICE_ANALOGIN - -#include "wait_api.h" -#include "cmsis.h" -#include "pinmap.h" -#include "PeripheralPins.h" - -ADC_HandleTypeDef AdcHandle; - -int adc_inited = 0; - -void analogin_init(analogin_t *obj, PinName pin) -{ - // Get the peripheral name from the pin and assign it to the object - obj->adc = (ADCName)pinmap_peripheral(pin, PinMap_ADC); - MBED_ASSERT(obj->adc != (ADCName)NC); - - // Configure GPIO - pinmap_pinout(pin, PinMap_ADC); - - // Save pin number for the read function - obj->pin = pin; - - // The ADC initialization is done once - if (adc_inited == 0) { - adc_inited = 1; - - // Enable ADC clock - __ADC1_CLK_ENABLE(); - - // Configure ADC - AdcHandle.Instance = (ADC_TypeDef *)(obj->adc); - AdcHandle.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV4; - AdcHandle.Init.Resolution = ADC_RESOLUTION12b; - AdcHandle.Init.DataAlign = ADC_DATAALIGN_RIGHT; - AdcHandle.Init.ScanConvMode = DISABLE; - AdcHandle.Init.EOCSelection = EOC_SINGLE_CONV; - AdcHandle.Init.LowPowerAutoWait = DISABLE; - AdcHandle.Init.LowPowerAutoPowerOff = DISABLE; - AdcHandle.Init.ContinuousConvMode = DISABLE; - AdcHandle.Init.DiscontinuousConvMode = DISABLE; - AdcHandle.Init.ExternalTrigConv = ADC_SOFTWARE_START; - AdcHandle.Init.ExternalTrigConvEdge = ADC_EXTERNALTRIGCONVEDGE_NONE; - AdcHandle.Init.DMAContinuousRequests = DISABLE; - AdcHandle.Init.Overrun = OVR_DATA_OVERWRITTEN; - HAL_ADC_Init(&AdcHandle); - - // Run the ADC calibration - HAL_ADCEx_Calibration_Start(&AdcHandle); - } -} - -static inline uint16_t adc_read(analogin_t *obj) -{ - ADC_ChannelConfTypeDef sConfig; - - AdcHandle.Instance = (ADC_TypeDef *)(obj->adc); - - // Configure ADC channel - sConfig.Rank = ADC_RANK_CHANNEL_NUMBER; - sConfig.SamplingTime = ADC_SAMPLETIME_7CYCLES_5; - - switch (obj->pin) { - case PA_0: - sConfig.Channel = ADC_CHANNEL_0; - break; - case PA_1: - sConfig.Channel = ADC_CHANNEL_1; - break; - case PA_2: - sConfig.Channel = ADC_CHANNEL_2; - break; - case PA_3: - sConfig.Channel = ADC_CHANNEL_3; - break; - case PA_4: - sConfig.Channel = ADC_CHANNEL_4; - break; - case PA_5: - sConfig.Channel = ADC_CHANNEL_5; - break; - case PA_6: - sConfig.Channel = ADC_CHANNEL_6; - break; - case PA_7: - sConfig.Channel = ADC_CHANNEL_7; - break; - case PB_0: - sConfig.Channel = ADC_CHANNEL_8; - break; - case PB_1: - sConfig.Channel = ADC_CHANNEL_9; - break; - case PC_0: - sConfig.Channel = ADC_CHANNEL_10; - break; - case PC_1: - sConfig.Channel = ADC_CHANNEL_11; - break; - case PC_2: - sConfig.Channel = ADC_CHANNEL_12; - break; - case PC_3: - sConfig.Channel = ADC_CHANNEL_13; - break; - case PC_4: - sConfig.Channel = ADC_CHANNEL_14; - break; - case PC_5: - sConfig.Channel = ADC_CHANNEL_15; - break; - default: - return 0; - } - - // Clear all channels as it is not done in HAL_ADC_ConfigChannel() - AdcHandle.Instance->CHSELR = 0; - - HAL_ADC_ConfigChannel(&AdcHandle, &sConfig); - - HAL_ADC_Start(&AdcHandle); // Start conversion - - // Wait end of conversion and get value - if (HAL_ADC_PollForConversion(&AdcHandle, 10) == HAL_OK) { - return (HAL_ADC_GetValue(&AdcHandle)); - } else { - return 0; - } -} - -uint16_t analogin_read_u16(analogin_t *obj) -{ - uint16_t value = adc_read(obj); - // 12-bit to 16-bit conversion - value = ((value << 4) & (uint16_t)0xFFF0) | ((value >> 8) & (uint16_t)0x000F); - return value; -} - -float analogin_read(analogin_t *obj) -{ - uint16_t value = adc_read(obj); - return (float)value * (1.0f / (float)0xFFF); // 12 bits range -} - -#endif diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/gpio_api.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/gpio_api.c deleted file mode 100644 index 48fb0b5d54..0000000000 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/gpio_api.c +++ /dev/null @@ -1,79 +0,0 @@ -/* mbed Microcontroller Library - ******************************************************************************* - * Copyright (c) 2014, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - ******************************************************************************* - */ -#include "mbed_assert.h" -#include "gpio_api.h" -#include "pinmap.h" -#include "mbed_error.h" - -extern uint32_t Set_GPIO_Clock(uint32_t port_idx); - -uint32_t gpio_set(PinName pin) -{ - MBED_ASSERT(pin != (PinName)NC); - - pin_function(pin, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)); - - return (uint32_t)(1 << ((uint32_t)pin & 0xF)); // Return the pin mask -} - -void gpio_init(gpio_t *obj, PinName pin) -{ - obj->pin = pin; - if (pin == (PinName)NC) { - return; - } - - uint32_t port_index = STM_PORT(pin); - - // Enable GPIO clock - uint32_t gpio_add = Set_GPIO_Clock(port_index); - GPIO_TypeDef *gpio = (GPIO_TypeDef *)gpio_add; - - // Fill GPIO object structure for future use - obj->mask = gpio_set(pin); - obj->reg_in = &gpio->IDR; - obj->reg_set = &gpio->BSRR; - obj->reg_clr = &gpio->BRR; -} - -void gpio_mode(gpio_t *obj, PinMode mode) -{ - pin_mode(obj->pin, mode); -} - -void gpio_dir(gpio_t *obj, PinDirection direction) -{ - MBED_ASSERT(obj->pin != (PinName)NC); - if (direction == PIN_OUTPUT) { - pin_function(obj->pin, STM_PIN_DATA(STM_MODE_OUTPUT_PP, GPIO_NOPULL, 0)); - } else { // PIN_INPUT - pin_function(obj->pin, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)); - } -} diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/gpio_irq_api.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/gpio_irq_api.c deleted file mode 100644 index 37bb383f30..0000000000 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/gpio_irq_api.c +++ /dev/null @@ -1,268 +0,0 @@ -/* mbed Microcontroller Library - ******************************************************************************* - * Copyright (c) 2014, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - ******************************************************************************* - */ -#include -#include "cmsis.h" - -#include "gpio_irq_api.h" -#include "pinmap.h" -#include "mbed_error.h" - -#define EDGE_NONE (0) -#define EDGE_RISE (1) -#define EDGE_FALL (2) -#define EDGE_BOTH (3) - -// Number of EXTI irq vectors (EXTI0_1, EXTI2_3, EXTI4_15) -#define CHANNEL_NUM (3) - -// Max pins for one line (max with EXTI4_15) -#define MAX_PIN_LINE (12) - -typedef struct gpio_channel { - uint32_t pin_mask; // bitmask representing which pins are configured for receiving interrupts - uint32_t channel_ids[MAX_PIN_LINE]; // mbed "gpio_irq_t gpio_irq" field of instance - uint32_t channel_gpio[MAX_PIN_LINE]; // base address of gpio port group - uint32_t channel_pin[MAX_PIN_LINE]; // pin number in port group -} gpio_channel_t; - -static gpio_channel_t channels[CHANNEL_NUM] = { - {.pin_mask = 0}, - {.pin_mask = 0}, - {.pin_mask = 0} -}; - -// Used to return the index for channels array. -static uint32_t pin_base_nr[16] = { - // EXTI0_1 - 0, // pin 0 - 1, // pin 1 - // EXTI2_3 - 0, // pin 2 - 1, // pin 3 - // EXTI4_15 - 0, // pin 4 - 1, // pin 5 - 2, // pin 6 - 3, // pin 7 - 4, // pin 8 - 5, // pin 9 - 6, // pin 10 - 7, // pin 11 - 8, // pin 12 - 9, // pin 13 - 10, // pin 14 - 11 // pin 15 -}; - -static gpio_irq_handler irq_handler; - -static void handle_interrupt_in(uint32_t irq_index, uint32_t max_num_pin_line) -{ - gpio_channel_t *gpio_channel = &channels[irq_index]; - uint32_t gpio_idx; - - for (gpio_idx = 0; gpio_idx < max_num_pin_line; gpio_idx++) { - uint32_t current_mask = (1 << gpio_idx); - - if (gpio_channel->pin_mask & current_mask) { - // Retrieve the gpio and pin that generate the irq - GPIO_TypeDef *gpio = (GPIO_TypeDef *)(gpio_channel->channel_gpio[gpio_idx]); - uint32_t pin = (uint32_t)(1 << (gpio_channel->channel_pin[gpio_idx])); - - // Clear interrupt flag - if (__HAL_GPIO_EXTI_GET_FLAG(pin) != RESET) { - __HAL_GPIO_EXTI_CLEAR_FLAG(pin); - - if (gpio_channel->channel_ids[gpio_idx] == 0) continue; - - // Check which edge has generated the irq - if ((gpio->IDR & pin) == 0) { - irq_handler(gpio_channel->channel_ids[gpio_idx], IRQ_FALL); - } else { - irq_handler(gpio_channel->channel_ids[gpio_idx], IRQ_RISE); - } - } - } - } -} - -// EXTI lines 0 to 1 -static void gpio_irq0(void) -{ - handle_interrupt_in(0, 2); -} - -// EXTI lines 2 to 3 -static void gpio_irq1(void) -{ - handle_interrupt_in(1, 2); -} - -// EXTI lines 4 to 15 -static void gpio_irq2(void) -{ - handle_interrupt_in(2, 12); -} - -extern uint32_t Set_GPIO_Clock(uint32_t port_idx); - -int gpio_irq_init(gpio_irq_t *obj, PinName pin, gpio_irq_handler handler, uint32_t id) -{ - IRQn_Type irq_n = (IRQn_Type)0; - uint32_t vector = 0; - uint32_t irq_index; - gpio_channel_t *gpio_channel; - uint32_t gpio_idx; - - if (pin == NC) return -1; - - uint32_t port_index = STM_PORT(pin); - uint32_t pin_index = STM_PIN(pin); - - // Select irq number and interrupt routine - if ((pin_index == 0) || (pin_index == 1)) { - irq_n = EXTI0_1_IRQn; - vector = (uint32_t)&gpio_irq0; - irq_index = 0; - } else if ((pin_index == 2) || (pin_index == 3)) { - irq_n = EXTI2_3_IRQn; - vector = (uint32_t)&gpio_irq1; - irq_index = 1; - } else if ((pin_index > 3) && (pin_index < 16)) { - irq_n = EXTI4_15_IRQn; - vector = (uint32_t)&gpio_irq2; - irq_index = 2; - } else { - error("InterruptIn error: pin not supported.\n"); - return -1; - } - - // Enable GPIO clock - uint32_t gpio_add = Set_GPIO_Clock(port_index); - - // Configure GPIO - pin_function(pin, STM_PIN_DATA(STM_MODE_IT_FALLING, GPIO_NOPULL, 0)); - - // Enable EXTI interrupt - NVIC_SetVector(irq_n, vector); - NVIC_EnableIRQ(irq_n); - - // Save informations for future use - obj->irq_n = irq_n; - obj->irq_index = irq_index; - obj->event = EDGE_NONE; - obj->pin = pin; - - gpio_channel = &channels[irq_index]; - gpio_idx = pin_base_nr[pin_index]; - gpio_channel->pin_mask |= (1 << gpio_idx); - gpio_channel->channel_ids[gpio_idx] = id; - gpio_channel->channel_gpio[gpio_idx] = gpio_add; - gpio_channel->channel_pin[gpio_idx] = pin_index; - - irq_handler = handler; - - return 0; -} - -void gpio_irq_free(gpio_irq_t *obj) -{ - gpio_channel_t *gpio_channel = &channels[obj->irq_index]; - uint32_t pin_index = STM_PIN(obj->pin); - uint32_t gpio_idx = pin_base_nr[pin_index]; - - gpio_channel->pin_mask &= ~(1 << gpio_idx); - gpio_channel->channel_ids[gpio_idx] = 0; - gpio_channel->channel_gpio[gpio_idx] = 0; - gpio_channel->channel_pin[gpio_idx] = 0; - - // Disable EXTI line - pin_function(obj->pin, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)); - obj->event = EDGE_NONE; -} - -void gpio_irq_set(gpio_irq_t *obj, gpio_irq_event event, uint32_t enable) -{ - uint32_t mode = STM_MODE_IT_EVT_RESET; - uint32_t pull = GPIO_NOPULL; - - if (enable) { - if (event == IRQ_RISE) { - if ((obj->event == EDGE_FALL) || (obj->event == EDGE_BOTH)) { - mode = STM_MODE_IT_RISING_FALLING; - obj->event = EDGE_BOTH; - } else { // NONE or RISE - mode = STM_MODE_IT_RISING; - obj->event = EDGE_RISE; - } - } - if (event == IRQ_FALL) { - if ((obj->event == EDGE_RISE) || (obj->event == EDGE_BOTH)) { - mode = STM_MODE_IT_RISING_FALLING; - obj->event = EDGE_BOTH; - } else { // NONE or FALL - mode = STM_MODE_IT_FALLING; - obj->event = EDGE_FALL; - } - } - } else { // Disable - if (event == IRQ_RISE) { - if ((obj->event == EDGE_FALL) || (obj->event == EDGE_BOTH)) { - mode = STM_MODE_IT_FALLING; - obj->event = EDGE_FALL; - } else { // NONE or RISE - mode = STM_MODE_IT_EVT_RESET; - obj->event = EDGE_NONE; - } - } - if (event == IRQ_FALL) { - if ((obj->event == EDGE_RISE) || (obj->event == EDGE_BOTH)) { - mode = STM_MODE_IT_RISING; - obj->event = EDGE_RISE; - } else { // NONE or FALL - mode = STM_MODE_IT_EVT_RESET; - obj->event = EDGE_NONE; - } - } - } - - pin_function(obj->pin, STM_PIN_DATA(mode, pull, 0)); -} - -void gpio_irq_enable(gpio_irq_t *obj) -{ - NVIC_EnableIRQ(obj->irq_n); -} - -void gpio_irq_disable(gpio_irq_t *obj) -{ - NVIC_DisableIRQ(obj->irq_n); - obj->event = EDGE_NONE; -} diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/gpio_object.h b/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/gpio_object.h deleted file mode 100644 index 684d968757..0000000000 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/gpio_object.h +++ /dev/null @@ -1,75 +0,0 @@ -/* mbed Microcontroller Library - ******************************************************************************* - * Copyright (c) 2014, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - ******************************************************************************* - */ -#ifndef MBED_GPIO_OBJECT_H -#define MBED_GPIO_OBJECT_H - -#include "mbed_assert.h" -#include "cmsis.h" -#include "PortNames.h" -#include "PeripheralNames.h" -#include "PinNames.h" - -#ifdef __cplusplus -extern "C" { -#endif - -typedef struct { - PinName pin; - uint32_t mask; - __IO uint32_t *reg_in; - __IO uint32_t *reg_set; - __IO uint32_t *reg_clr; -} gpio_t; - -static inline void gpio_write(gpio_t *obj, int value) -{ - MBED_ASSERT(obj->pin != (PinName)NC); - if (value) { - *obj->reg_set = obj->mask; - } else { - *obj->reg_clr = obj->mask; - } -} - -static inline int gpio_read(gpio_t *obj) -{ - MBED_ASSERT(obj->pin != (PinName)NC); - return ((*obj->reg_in & obj->mask) ? 1 : 0); -} - -static inline int gpio_is_connected(const gpio_t *obj) { - return obj->pin != (PinName)NC; -} - -#ifdef __cplusplus -} -#endif - -#endif diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/i2c_api.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/i2c_api.c deleted file mode 100644 index 12d245cbb0..0000000000 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/i2c_api.c +++ /dev/null @@ -1,390 +0,0 @@ -/* mbed Microcontroller Library - ******************************************************************************* - * Copyright (c) 2014, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - ******************************************************************************* - */ -#include "mbed_assert.h" -#include "i2c_api.h" - -#if DEVICE_I2C - -#include "cmsis.h" -#include "pinmap.h" -#include "PeripheralPins.h" - -/* Timeout values for flags and events waiting loops. These timeouts are - not based on accurate values, they just guarantee that the application will - not remain stuck if the I2C communication is corrupted. */ -#define FLAG_TIMEOUT ((int)0x1000) -#define LONG_TIMEOUT ((int)0x8000) - -I2C_HandleTypeDef I2cHandle; - -int i2c1_inited = 0; -int i2c2_inited = 0; - -void i2c_init(i2c_t *obj, PinName sda, PinName scl) -{ - // Determine the I2C to use - I2CName i2c_sda = (I2CName)pinmap_peripheral(sda, PinMap_I2C_SDA); - I2CName i2c_scl = (I2CName)pinmap_peripheral(scl, PinMap_I2C_SCL); - - obj->i2c = (I2CName)pinmap_merge(i2c_sda, i2c_scl); - MBED_ASSERT(obj->i2c != (I2CName)NC); - - // Enable I2C1 clock and pinout if not done - if ((obj->i2c == I2C_1) && !i2c1_inited) { - i2c1_inited = 1; - __HAL_RCC_I2C1_CONFIG(RCC_I2C1CLKSOURCE_SYSCLK); - __I2C1_CLK_ENABLE(); - // Configure I2C pins - pinmap_pinout(sda, PinMap_I2C_SDA); - pinmap_pinout(scl, PinMap_I2C_SCL); - pin_mode(sda, OpenDrain); - pin_mode(scl, OpenDrain); - } - - // Enable I2C2 clock and pinout if not done - if ((obj->i2c == I2C_2) && !i2c2_inited) { - i2c2_inited = 1; - __I2C2_CLK_ENABLE(); - // Configure I2C pins - pinmap_pinout(sda, PinMap_I2C_SDA); - pinmap_pinout(scl, PinMap_I2C_SCL); - pin_mode(sda, OpenDrain); - pin_mode(scl, OpenDrain); - } - - // Reset to clear pending flags if any - i2c_reset(obj); - - // I2C configuration - i2c_frequency(obj, 100000); // 100 kHz per default -} - -void i2c_frequency(i2c_t *obj, int hz) -{ - MBED_ASSERT((hz == 100000) || (hz == 400000) || (hz == 1000000)); - I2cHandle.Instance = (I2C_TypeDef *)(obj->i2c); - int timeout; - - // wait before init - timeout = LONG_TIMEOUT; - while ((__HAL_I2C_GET_FLAG(&I2cHandle, I2C_FLAG_BUSY)) && (timeout-- != 0)); - - // Common settings: I2C clock = 48 MHz, Analog filter = ON, Digital filter coefficient = 0 - switch (hz) { - case 100000: - I2cHandle.Init.Timing = 0x10805E89; // Standard mode with Rise Time = 400ns and Fall Time = 100ns - break; - case 400000: - I2cHandle.Init.Timing = 0x00901850; // Fast mode with Rise Time = 250ns and Fall Time = 100ns - break; - case 1000000: - I2cHandle.Init.Timing = 0x00700818; // Fast mode Plus with Rise Time = 60ns and Fall Time = 100ns - break; - default: - break; - } - - // I2C configuration - I2cHandle.Init.AddressingMode = I2C_ADDRESSINGMODE_7BIT; - I2cHandle.Init.DualAddressMode = I2C_DUALADDRESS_DISABLED; - I2cHandle.Init.GeneralCallMode = I2C_GENERALCALL_DISABLED; - I2cHandle.Init.NoStretchMode = I2C_NOSTRETCH_DISABLED; - I2cHandle.Init.OwnAddress1 = 0; - I2cHandle.Init.OwnAddress2 = 0; - I2cHandle.Init.OwnAddress2Masks = I2C_OA2_NOMASK; - HAL_I2C_Init(&I2cHandle); -} - -inline int i2c_start(i2c_t *obj) -{ - I2C_TypeDef *i2c = (I2C_TypeDef *)(obj->i2c); - int timeout; - - I2cHandle.Instance = (I2C_TypeDef *)(obj->i2c); - - // Clear Acknowledge failure flag - __HAL_I2C_CLEAR_FLAG(&I2cHandle, I2C_FLAG_AF); - - // Generate the START condition - i2c->CR2 |= I2C_CR2_START; - - // Wait the START condition has been correctly sent - timeout = FLAG_TIMEOUT; - while (__HAL_I2C_GET_FLAG(&I2cHandle, I2C_FLAG_BUSY) == RESET) { - if ((timeout--) == 0) { - return 1; - } - } - - return 0; -} - -inline int i2c_stop(i2c_t *obj) -{ - I2C_TypeDef *i2c = (I2C_TypeDef *)(obj->i2c); - - // Generate the STOP condition - i2c->CR2 |= I2C_CR2_STOP; - - return 0; -} - -int i2c_read(i2c_t *obj, int address, char *data, int length, int stop) -{ - I2C_TypeDef *i2c = (I2C_TypeDef *)(obj->i2c); - I2cHandle.Instance = (I2C_TypeDef *)(obj->i2c); - int timeout; - int count; - int value; - - // Update CR2 register - i2c->CR2 = (i2c->CR2 & (uint32_t)~((uint32_t)(I2C_CR2_SADD | I2C_CR2_NBYTES | I2C_CR2_RELOAD | I2C_CR2_AUTOEND | I2C_CR2_RD_WRN | I2C_CR2_START | I2C_CR2_STOP))) - | (uint32_t)(((uint32_t)address & I2C_CR2_SADD) | (((uint32_t)length << 16) & I2C_CR2_NBYTES) | (uint32_t)I2C_SOFTEND_MODE | (uint32_t)I2C_GENERATE_START_READ); - - // Read all bytes - for (count = 0; count < length; count++) { - value = i2c_byte_read(obj, 0); - data[count] = (char)value; - } - - // Wait transfer complete - timeout = FLAG_TIMEOUT; - while (__HAL_I2C_GET_FLAG(&I2cHandle, I2C_FLAG_TC) == RESET) { - timeout--; - if (timeout == 0) { - return -1; - } - } - __HAL_I2C_CLEAR_FLAG(&I2cHandle, I2C_FLAG_TC); - - // If not repeated start, send stop. - if (stop) { - i2c_stop(obj); - // Wait until STOPF flag is set - timeout = FLAG_TIMEOUT; - while (__HAL_I2C_GET_FLAG(&I2cHandle, I2C_FLAG_STOPF) == RESET) { - timeout--; - if (timeout == 0) { - return -1; - } - } - // Clear STOP Flag - __HAL_I2C_CLEAR_FLAG(&I2cHandle, I2C_FLAG_STOPF); - } - - return length; -} - -int i2c_write(i2c_t *obj, int address, const char *data, int length, int stop) -{ - I2C_TypeDef *i2c = (I2C_TypeDef *)(obj->i2c); - I2cHandle.Instance = (I2C_TypeDef *)(obj->i2c); - int timeout; - int count; - - // Update CR2 register - i2c->CR2 = (i2c->CR2 & (uint32_t)~((uint32_t)(I2C_CR2_SADD | I2C_CR2_NBYTES | I2C_CR2_RELOAD | I2C_CR2_AUTOEND | I2C_CR2_RD_WRN | I2C_CR2_START | I2C_CR2_STOP))) - | (uint32_t)(((uint32_t)address & I2C_CR2_SADD) | (((uint32_t)length << 16) & I2C_CR2_NBYTES) | (uint32_t)I2C_SOFTEND_MODE | (uint32_t)I2C_GENERATE_START_WRITE); - - for (count = 0; count < length; count++) { - i2c_byte_write(obj, data[count]); - } - - // Wait transfer complete - timeout = FLAG_TIMEOUT; - while (__HAL_I2C_GET_FLAG(&I2cHandle, I2C_FLAG_TC) == RESET) { - timeout--; - if (timeout == 0) { - return -1; - } - } - __HAL_I2C_CLEAR_FLAG(&I2cHandle, I2C_FLAG_TC); - - // If not repeated start, send stop - if (stop) { - i2c_stop(obj); - // Wait until STOPF flag is set - timeout = FLAG_TIMEOUT; - while (__HAL_I2C_GET_FLAG(&I2cHandle, I2C_FLAG_STOPF) == RESET) { - timeout--; - if (timeout == 0) { - return -1; - } - } - // Clear STOP Flag - __HAL_I2C_CLEAR_FLAG(&I2cHandle, I2C_FLAG_STOPF); - } - - return count; -} - -int i2c_byte_read(i2c_t *obj, int last) -{ - I2C_TypeDef *i2c = (I2C_TypeDef *)(obj->i2c); - int timeout; - - // Wait until the byte is received - timeout = FLAG_TIMEOUT; - while (__HAL_I2C_GET_FLAG(&I2cHandle, I2C_FLAG_RXNE) == RESET) { - if ((timeout--) == 0) { - return -1; - } - } - - return (int)i2c->RXDR; -} - -int i2c_byte_write(i2c_t *obj, int data) -{ - I2C_TypeDef *i2c = (I2C_TypeDef *)(obj->i2c); - int timeout; - - // Wait until the previous byte is transmitted - timeout = FLAG_TIMEOUT; - while (__HAL_I2C_GET_FLAG(&I2cHandle, I2C_FLAG_TXIS) == RESET) { - if ((timeout--) == 0) { - return 0; - } - } - - i2c->TXDR = (uint8_t)data; - - return 1; -} - -void i2c_reset(i2c_t *obj) -{ - int timeout; - - // Wait before reset - timeout = LONG_TIMEOUT; - while ((__HAL_I2C_GET_FLAG(&I2cHandle, I2C_FLAG_BUSY)) && (timeout-- != 0)); - - if (obj->i2c == I2C_1) { - __I2C1_FORCE_RESET(); - __I2C1_RELEASE_RESET(); - } - if (obj->i2c == I2C_2) { - __I2C2_FORCE_RESET(); - __I2C2_RELEASE_RESET(); - } -} - -#if DEVICE_I2CSLAVE - -void i2c_slave_address(i2c_t *obj, int idx, uint32_t address, uint32_t mask) -{ - I2C_TypeDef *i2c = (I2C_TypeDef *)(obj->i2c); - uint16_t tmpreg = 0; - - // disable - i2c->OAR1 &= (uint32_t)(~I2C_OAR1_OA1EN); - // Get the old register value - tmpreg = i2c->OAR1; - // Reset address bits - tmpreg &= 0xFC00; - // Set new address - tmpreg |= (uint16_t)((uint16_t)address & (uint16_t)0x00FE); // 7-bits - // Store the new register value - i2c->OAR1 = tmpreg; - // enable - i2c->OAR1 |= I2C_OAR1_OA1EN; -} - -void i2c_slave_mode(i2c_t *obj, int enable_slave) -{ - I2C_TypeDef *i2c = (I2C_TypeDef *)(obj->i2c); - uint16_t tmpreg; - - // Get the old register value - tmpreg = i2c->OAR1; - - // Enable / disable slave - if (enable_slave == 1) { - tmpreg |= I2C_OAR1_OA1EN; - } else { - tmpreg &= (uint32_t)(~I2C_OAR1_OA1EN); - } - - // Set new mode - i2c->OAR1 = tmpreg; -} - -// See I2CSlave.h -#define NoData 0 // the slave has not been addressed -#define ReadAddressed 1 // the master has requested a read from this slave (slave = transmitter) -#define WriteGeneral 2 // the master is writing to all slave -#define WriteAddressed 3 // the master is writing to this slave (slave = receiver) - -int i2c_slave_receive(i2c_t *obj) -{ - I2cHandle.Instance = (I2C_TypeDef *)(obj->i2c); - int retValue = NoData; - - if (__HAL_I2C_GET_FLAG(&I2cHandle, I2C_FLAG_BUSY) == 1) { - if (__HAL_I2C_GET_FLAG(&I2cHandle, I2C_FLAG_ADDR) == 1) { - if (__HAL_I2C_GET_FLAG(&I2cHandle, I2C_FLAG_DIR) == 1) - retValue = ReadAddressed; - else - retValue = WriteAddressed; - - __HAL_I2C_CLEAR_FLAG(&I2cHandle, I2C_FLAG_ADDR); - } - } - - return (retValue); -} - -int i2c_slave_read(i2c_t *obj, char *data, int length) -{ - int size = 0; - - while (size < length) data[size++] = (char)i2c_byte_read(obj, 0); - - return size; -} - -int i2c_slave_write(i2c_t *obj, const char *data, int length) -{ - int size = 0; - I2cHandle.Instance = (I2C_TypeDef *)(obj->i2c); - - do { - i2c_byte_write(obj, data[size]); - size++; - } while (size < length); - - return size; -} - - -#endif // DEVICE_I2CSLAVE - -#endif // DEVICE_I2C diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/mbed_overrides.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/mbed_overrides.c deleted file mode 100644 index 74ce0cf19d..0000000000 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/mbed_overrides.c +++ /dev/null @@ -1,35 +0,0 @@ -/* mbed Microcontroller Library - * Copyright (c) 2014, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#include "cmsis.h" - -// This function is called after RAM initialization and before main. -void mbed_sdk_init() -{ - // Update the SystemCoreClock variable. - SystemCoreClockUpdate(); -} diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/pinmap.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/pinmap.c deleted file mode 100644 index dfb070f482..0000000000 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/pinmap.c +++ /dev/null @@ -1,137 +0,0 @@ -/* mbed Microcontroller Library - ******************************************************************************* - * Copyright (c) 2014, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - ******************************************************************************* - */ -#include "mbed_assert.h" -#include "pinmap.h" -#include "PortNames.h" -#include "mbed_error.h" - -// GPIO mode look-up table -static const uint32_t gpio_mode[13] = { - 0x00000000, // 0 = GPIO_MODE_INPUT - 0x00000001, // 1 = GPIO_MODE_OUTPUT_PP - 0x00000011, // 2 = GPIO_MODE_OUTPUT_OD - 0x00000002, // 3 = GPIO_MODE_AF_PP - 0x00000012, // 4 = GPIO_MODE_AF_OD - 0x00000003, // 5 = GPIO_MODE_ANALOG - 0x10110000, // 6 = GPIO_MODE_IT_RISING - 0x10210000, // 7 = GPIO_MODE_IT_FALLING - 0x10310000, // 8 = GPIO_MODE_IT_RISING_FALLING - 0x10120000, // 9 = GPIO_MODE_EVT_RISING - 0x10220000, // 10 = GPIO_MODE_EVT_FALLING - 0x10320000, // 11 = GPIO_MODE_EVT_RISING_FALLING - 0x10000000 // 12 = Reset IT and EVT (not in STM32Cube HAL) -}; - -// Enable GPIO clock and return GPIO base address -uint32_t Set_GPIO_Clock(uint32_t port_idx) -{ - uint32_t gpio_add = 0; - switch (port_idx) { - case PortA: - gpio_add = GPIOA_BASE; - __GPIOA_CLK_ENABLE(); - break; - case PortB: - gpio_add = GPIOB_BASE; - __GPIOB_CLK_ENABLE(); - break; - case PortC: - gpio_add = GPIOC_BASE; - __GPIOC_CLK_ENABLE(); - break; - case PortD: - gpio_add = GPIOD_BASE; - __GPIOD_CLK_ENABLE(); - break; - case PortF: - gpio_add = GPIOF_BASE; - __GPIOF_CLK_ENABLE(); - break; - default: - error("Pinmap error: wrong port number."); - break; - } - return gpio_add; -} - -/** - * Configure pin (mode, speed, output type and pull-up/pull-down) - */ -void pin_function(PinName pin, int data) -{ - MBED_ASSERT(pin != (PinName)NC); - // Get the pin informations - uint32_t mode = STM_PIN_MODE(data); - uint32_t pupd = STM_PIN_PUPD(data); - uint32_t afnum = STM_PIN_AFNUM(data); - - uint32_t port_index = STM_PORT(pin); - uint32_t pin_index = STM_PIN(pin); - - // Enable GPIO clock - uint32_t gpio_add = Set_GPIO_Clock(port_index); - GPIO_TypeDef *gpio = (GPIO_TypeDef *)gpio_add; - - // Configure GPIO - GPIO_InitTypeDef GPIO_InitStructure; - GPIO_InitStructure.Pin = (uint32_t)(1 << pin_index); - GPIO_InitStructure.Mode = gpio_mode[mode]; - GPIO_InitStructure.Pull = pupd; - GPIO_InitStructure.Speed = GPIO_SPEED_HIGH; - GPIO_InitStructure.Alternate = afnum; - HAL_GPIO_Init(gpio, &GPIO_InitStructure); - - // [TODO] Disconnect SWDIO and SWCLK signals ? - // Warning: For debugging it is necessary to reconnect under reset if this is done. - //if ((pin == PA_13) || (pin == PA_14)) { - // - //} -} - -/** - * Configure pin pull-up/pull-down - */ -void pin_mode(PinName pin, PinMode mode) -{ - MBED_ASSERT(pin != (PinName)NC); - uint32_t port_index = STM_PORT(pin); - uint32_t pin_index = STM_PIN(pin); - - // Enable GPIO clock - uint32_t gpio_add = Set_GPIO_Clock(port_index); - GPIO_TypeDef *gpio = (GPIO_TypeDef *)gpio_add; - - // Configure pull-up/pull-down resistors - uint32_t pupd = (uint32_t)mode; - if (pupd > 2) pupd = 0; // Open-drain = No pull-up/No pull-down - gpio->PUPDR &= (uint32_t)(~(GPIO_PUPDR_PUPDR0 << (pin_index * 2))); - gpio->PUPDR |= (uint32_t)(pupd << (pin_index * 2)); - -} diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/port_api.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/port_api.c deleted file mode 100644 index ecfded6e59..0000000000 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/port_api.c +++ /dev/null @@ -1,103 +0,0 @@ -/* mbed Microcontroller Library - ******************************************************************************* - * Copyright (c) 2014, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - ******************************************************************************* - */ -#include "port_api.h" -#include "pinmap.h" -#include "gpio_api.h" -#include "mbed_error.h" - -#if DEVICE_PORTIN || DEVICE_PORTOUT - -extern uint32_t Set_GPIO_Clock(uint32_t port_idx); - -// high nibble = port number (0=A, 1=B, 2=C, 3=D, 4=E, 5=F, ...) -// low nibble = pin number -PinName port_pin(PortName port, int pin_n) -{ - return (PinName)(pin_n + (port << 4)); -} - -void port_init(port_t *obj, PortName port, int mask, PinDirection dir) -{ - uint32_t port_index = (uint32_t)port; - - // Enable GPIO clock - uint32_t gpio_add = Set_GPIO_Clock(port_index); - GPIO_TypeDef *gpio = (GPIO_TypeDef *)gpio_add; - - // Fill PORT object structure for future use - obj->port = port; - obj->mask = mask; - obj->direction = dir; - obj->reg_in = &gpio->IDR; - obj->reg_out = &gpio->ODR; - - port_dir(obj, dir); -} - -void port_dir(port_t *obj, PinDirection dir) -{ - uint32_t i; - obj->direction = dir; - for (i = 0; i < 16; i++) { // Process all pins - if (obj->mask & (1 << i)) { // If the pin is used - if (dir == PIN_OUTPUT) { - pin_function(port_pin(obj->port, i), STM_PIN_DATA(STM_MODE_OUTPUT_PP, GPIO_NOPULL, 0)); - } else { // PIN_INPUT - pin_function(port_pin(obj->port, i), STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)); - } - } - } -} - -void port_mode(port_t *obj, PinMode mode) -{ - uint32_t i; - for (i = 0; i < 16; i++) { // Process all pins - if (obj->mask & (1 << i)) { // If the pin is used - pin_mode(port_pin(obj->port, i), mode); - } - } -} - -void port_write(port_t *obj, int value) -{ - *obj->reg_out = (*obj->reg_out & ~obj->mask) | (value & obj->mask); -} - -int port_read(port_t *obj) -{ - if (obj->direction == PIN_OUTPUT) { - return (*obj->reg_out & obj->mask); - } else { // PIN_INPUT - return (*obj->reg_in & obj->mask); - } -} - -#endif diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/pwmout_api.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/pwmout_api.c deleted file mode 100644 index 916edd5013..0000000000 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/pwmout_api.c +++ /dev/null @@ -1,206 +0,0 @@ -/* mbed Microcontroller Library - ******************************************************************************* - * Copyright (c) 2014, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - ******************************************************************************* - */ -#include "pwmout_api.h" - -#if DEVICE_PWMOUT - -#include "cmsis.h" -#include "pinmap.h" -#include "mbed_error.h" -#include "PeripheralPins.h" - -static TIM_HandleTypeDef TimHandle; - -void pwmout_init(pwmout_t* obj, PinName pin) -{ - // Get the peripheral name from the pin and assign it to the object - obj->pwm = (PWMName)pinmap_peripheral(pin, PinMap_PWM); - - if (obj->pwm == (PWMName)NC) { - error("PWM error: pinout mapping failed."); - } - - // Enable TIM clock - if (obj->pwm == PWM_3) __TIM3_CLK_ENABLE(); - if (obj->pwm == PWM_14) __TIM14_CLK_ENABLE(); - if (obj->pwm == PWM_15) __TIM15_CLK_ENABLE(); - if (obj->pwm == PWM_16) __TIM16_CLK_ENABLE(); - if (obj->pwm == PWM_17) __TIM17_CLK_ENABLE(); - - // Configure GPIO - pinmap_pinout(pin, PinMap_PWM); - - obj->pin = pin; - obj->period = 0; - obj->pulse = 0; - - pwmout_period_us(obj, 20000); // 20 ms per default -} - -void pwmout_free(pwmout_t* obj) -{ - // Configure GPIO - pin_function(obj->pin, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)); -} - -void pwmout_write(pwmout_t* obj, float value) -{ - TIM_OC_InitTypeDef sConfig; - int channel = 0; - int complementary_channel = 0; - - TimHandle.Instance = (TIM_TypeDef *)(obj->pwm); - - if (value < (float)0.0) { - value = 0.0; - } else if (value > (float)1.0) { - value = 1.0; - } - - obj->pulse = (uint32_t)((float)obj->period * value); - - // Configure channels - sConfig.OCMode = TIM_OCMODE_PWM1; - sConfig.Pulse = obj->pulse; - sConfig.OCPolarity = TIM_OCPOLARITY_HIGH; - sConfig.OCNPolarity = TIM_OCNPOLARITY_HIGH; - sConfig.OCFastMode = TIM_OCFAST_DISABLE; - sConfig.OCIdleState = TIM_OCIDLESTATE_RESET; - sConfig.OCNIdleState = TIM_OCNIDLESTATE_RESET; - - switch (obj->pin) { - // Channels 1 - case PA_4: - case PA_6: - case PB_1: - case PB_4: - case PB_8: - case PB_9: - case PB_14: - case PC_6: - channel = TIM_CHANNEL_1; - break; - // Channels 1N - case PB_6: - case PB_7: - channel = TIM_CHANNEL_1; - complementary_channel = 1; - break; - // Channels 2 - case PA_7: - case PB_5: - case PB_15: - case PC_7: - channel = TIM_CHANNEL_2; - break; - // Channels 3 - case PB_0: - case PC_8: - channel = TIM_CHANNEL_3; - break; - // Channels 4 - case PC_9: - channel = TIM_CHANNEL_4; - break; - default: - return; - } - - HAL_TIM_PWM_ConfigChannel(&TimHandle, &sConfig, channel); - - if (complementary_channel) { - HAL_TIMEx_PWMN_Start(&TimHandle, channel); - } else { - HAL_TIM_PWM_Start(&TimHandle, channel); - } -} - -float pwmout_read(pwmout_t* obj) -{ - float value = 0; - if (obj->period > 0) { - value = (float)(obj->pulse) / (float)(obj->period); - } - return ((value > (float)1.0) ? (float)(1.0) : (value)); -} - -void pwmout_period(pwmout_t* obj, float seconds) -{ - pwmout_period_us(obj, seconds * 1000000.0f); -} - -void pwmout_period_ms(pwmout_t* obj, int ms) -{ - pwmout_period_us(obj, ms * 1000); -} - -void pwmout_period_us(pwmout_t* obj, int us) -{ - TimHandle.Instance = (TIM_TypeDef *)(obj->pwm); - - float dc = pwmout_read(obj); - - __HAL_TIM_DISABLE(&TimHandle); - - // Update the SystemCoreClock variable - SystemCoreClockUpdate(); - - TimHandle.Init.Period = us - 1; - TimHandle.Init.Prescaler = (uint16_t)(SystemCoreClock / 1000000) - 1; // 1 µs tick - TimHandle.Init.ClockDivision = 0; - TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP; - HAL_TIM_PWM_Init(&TimHandle); - - // Set duty cycle again - pwmout_write(obj, dc); - - // Save for future use - obj->period = us; - - __HAL_TIM_ENABLE(&TimHandle); -} - -void pwmout_pulsewidth(pwmout_t* obj, float seconds) -{ - pwmout_pulsewidth_us(obj, seconds * 1000000.0f); -} - -void pwmout_pulsewidth_ms(pwmout_t* obj, int ms) -{ - pwmout_pulsewidth_us(obj, ms * 1000); -} - -void pwmout_pulsewidth_us(pwmout_t* obj, int us) -{ - float value = (float)us / (float)obj->period; - pwmout_write(obj, value); -} - -#endif diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/rtc_api.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/rtc_api.c deleted file mode 100644 index c46a7d3935..0000000000 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/rtc_api.c +++ /dev/null @@ -1,201 +0,0 @@ -/* mbed Microcontroller Library - ******************************************************************************* - * Copyright (c) 2014, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - ******************************************************************************* - */ -#include "rtc_api.h" - -#if DEVICE_RTC - -#include "mbed_error.h" - -static int rtc_inited = 0; - -static RTC_HandleTypeDef RtcHandle; - -void rtc_init(void) -{ - RCC_OscInitTypeDef RCC_OscInitStruct; - uint32_t rtc_freq = 0; - - if (rtc_inited) return; - rtc_inited = 1; - - RtcHandle.Instance = RTC; - - // Enable Power clock - __PWR_CLK_ENABLE(); - - // Enable access to Backup domain - HAL_PWR_EnableBkUpAccess(); - - // Reset Backup domain - __HAL_RCC_BACKUPRESET_FORCE(); - __HAL_RCC_BACKUPRESET_RELEASE(); - - // Enable LSE Oscillator - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSE; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; // Mandatory, otherwise the PLL is reconfigured! - RCC_OscInitStruct.LSEState = RCC_LSE_ON; // External 32.768 kHz clock on OSC_IN/OSC_OUT - if (HAL_RCC_OscConfig(&RCC_OscInitStruct) == HAL_OK) { - // Connect LSE to RTC - __HAL_RCC_RTC_CONFIG(RCC_RTCCLKSOURCE_LSE); - rtc_freq = LSE_VALUE; - } else { - // Enable LSI clock - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSI | RCC_OSCILLATORTYPE_LSE; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; // Mandatory, otherwise the PLL is reconfigured! - RCC_OscInitStruct.LSEState = RCC_LSE_OFF; - RCC_OscInitStruct.LSIState = RCC_LSI_ON; - if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK) { - error("RTC error: LSI clock initialization failed."); - } - // Connect LSI to RTC - __HAL_RCC_RTC_CONFIG(RCC_RTCCLKSOURCE_LSI); - // This value is LSI typical value. To be measured precisely using a timer input capture for example. - rtc_freq = LSI_VALUE; - } - - // Enable RTC - __HAL_RCC_RTC_ENABLE(); - - RtcHandle.Init.HourFormat = RTC_HOURFORMAT_24; - RtcHandle.Init.AsynchPrediv = 127; - RtcHandle.Init.SynchPrediv = (rtc_freq / 128) - 1; - RtcHandle.Init.OutPut = RTC_OUTPUT_DISABLE; - RtcHandle.Init.OutPutPolarity = RTC_OUTPUT_POLARITY_HIGH; - RtcHandle.Init.OutPutType = RTC_OUTPUT_TYPE_OPENDRAIN; - - if (HAL_RTC_Init(&RtcHandle) != HAL_OK) { - error("RTC error: RTC initialization failed."); - } -} - -void rtc_free(void) -{ - // Enable Power clock - __PWR_CLK_ENABLE(); - - // Enable access to Backup domain - HAL_PWR_EnableBkUpAccess(); - - // Reset Backup domain - __HAL_RCC_BACKUPRESET_FORCE(); - __HAL_RCC_BACKUPRESET_RELEASE(); - - // Disable access to Backup domain - HAL_PWR_DisableBkUpAccess(); - - // Disable LSI and LSE clocks - RCC_OscInitTypeDef RCC_OscInitStruct; - RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_LSI | RCC_OSCILLATORTYPE_LSE; - RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE; - RCC_OscInitStruct.LSIState = RCC_LSI_OFF; - RCC_OscInitStruct.LSEState = RCC_LSE_OFF; - HAL_RCC_OscConfig(&RCC_OscInitStruct); - - rtc_inited = 0; -} - -int rtc_isenabled(void) -{ - return rtc_inited; -} - -/* - RTC Registers - RTC_WeekDay 1=monday, 2=tuesday, ..., 7=sunday - RTC_Month 1=january, 2=february, ..., 12=december - RTC_Date day of the month 1-31 - RTC_Year year 0-99 - struct tm - tm_sec seconds after the minute 0-61 - tm_min minutes after the hour 0-59 - tm_hour hours since midnight 0-23 - tm_mday day of the month 1-31 - tm_mon months since January 0-11 - tm_year years since 1900 - tm_wday days since Sunday 0-6 - tm_yday days since January 1 0-365 - tm_isdst Daylight Saving Time flag -*/ -time_t rtc_read(void) -{ - RTC_DateTypeDef dateStruct; - RTC_TimeTypeDef timeStruct; - struct tm timeinfo; - - RtcHandle.Instance = RTC; - - // Read actual date and time - // Warning: the time must be read first! - HAL_RTC_GetTime(&RtcHandle, &timeStruct, FORMAT_BIN); - HAL_RTC_GetDate(&RtcHandle, &dateStruct, FORMAT_BIN); - - // Setup a tm structure based on the RTC - timeinfo.tm_wday = dateStruct.WeekDay; - timeinfo.tm_mon = dateStruct.Month - 1; - timeinfo.tm_mday = dateStruct.Date; - timeinfo.tm_year = dateStruct.Year + 100; - timeinfo.tm_hour = timeStruct.Hours; - timeinfo.tm_min = timeStruct.Minutes; - timeinfo.tm_sec = timeStruct.Seconds; - - // Convert to timestamp - time_t t = mktime(&timeinfo); - - return t; -} - -void rtc_write(time_t t) -{ - RTC_DateTypeDef dateStruct; - RTC_TimeTypeDef timeStruct; - - RtcHandle.Instance = RTC; - - // Convert the time into a tm - struct tm *timeinfo = localtime(&t); - - // Fill RTC structures - dateStruct.WeekDay = timeinfo->tm_wday; - dateStruct.Month = timeinfo->tm_mon + 1; - dateStruct.Date = timeinfo->tm_mday; - dateStruct.Year = timeinfo->tm_year - 100; - timeStruct.Hours = timeinfo->tm_hour; - timeStruct.Minutes = timeinfo->tm_min; - timeStruct.Seconds = timeinfo->tm_sec; - timeStruct.TimeFormat = RTC_HOURFORMAT12_PM; - timeStruct.DayLightSaving = RTC_DAYLIGHTSAVING_NONE; - timeStruct.StoreOperation = RTC_STOREOPERATION_RESET; - - // Change the RTC current date/time - HAL_RTC_SetDate(&RtcHandle, &dateStruct, FORMAT_BIN); - HAL_RTC_SetTime(&RtcHandle, &timeStruct, FORMAT_BIN); -} - -#endif diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/serial_api.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/serial_api.c deleted file mode 100644 index 6e33e5a95e..0000000000 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/serial_api.c +++ /dev/null @@ -1,322 +0,0 @@ -/* mbed Microcontroller Library - ******************************************************************************* - * Copyright (c) 2014, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - ******************************************************************************* - */ -#include "mbed_assert.h" -#include "serial_api.h" - -#if DEVICE_SERIAL - -#include "cmsis.h" -#include "pinmap.h" -#include -#include "PeripheralPins.h" - -#define UART_NUM (2) - -static uint32_t serial_irq_ids[UART_NUM] = {0, 0}; - -static uart_irq_handler irq_handler; - -UART_HandleTypeDef UartHandle; - -int stdio_uart_inited = 0; -serial_t stdio_uart; - -static void init_uart(serial_t *obj) -{ - UartHandle.Instance = (USART_TypeDef *)(obj->uart); - - UartHandle.Init.BaudRate = obj->baudrate; - UartHandle.Init.WordLength = obj->databits; - UartHandle.Init.StopBits = obj->stopbits; - UartHandle.Init.Parity = obj->parity; - UartHandle.Init.HwFlowCtl = UART_HWCONTROL_NONE; - - if (obj->pin_rx == NC) { - UartHandle.Init.Mode = UART_MODE_TX; - } else if (obj->pin_tx == NC) { - UartHandle.Init.Mode = UART_MODE_RX; - } else { - UartHandle.Init.Mode = UART_MODE_TX_RX; - } - - // Disable the reception overrun detection - UartHandle.AdvancedInit.AdvFeatureInit = UART_ADVFEATURE_RXOVERRUNDISABLE_INIT; - UartHandle.AdvancedInit.OverrunDisable = UART_ADVFEATURE_OVERRUN_DISABLE; - - HAL_UART_Init(&UartHandle); -} - -void serial_init(serial_t *obj, PinName tx, PinName rx) -{ - // Determine the UART to use (UART_1, UART_2, ...) - UARTName uart_tx = (UARTName)pinmap_peripheral(tx, PinMap_UART_TX); - UARTName uart_rx = (UARTName)pinmap_peripheral(rx, PinMap_UART_RX); - - // Get the peripheral name (UART_1, UART_2, ...) from the pin and assign it to the object - obj->uart = (UARTName)pinmap_merge(uart_tx, uart_rx); - MBED_ASSERT(obj->uart != (UARTName)NC); - - // Enable USART clock - if (obj->uart == UART_1) { - __USART1_CLK_ENABLE(); - obj->index = 0; - } - if (obj->uart == UART_2) { - __USART2_CLK_ENABLE(); - obj->index = 1; - } - - // Configure the UART pins - pinmap_pinout(tx, PinMap_UART_TX); - pinmap_pinout(rx, PinMap_UART_RX); - if (tx != NC) { - pin_mode(tx, PullUp); - } - if (rx != NC) { - pin_mode(rx, PullUp); - } - - // Configure UART - obj->baudrate = 9600; - obj->databits = UART_WORDLENGTH_8B; - obj->stopbits = UART_STOPBITS_1; - obj->parity = UART_PARITY_NONE; - - obj->pin_tx = tx; - obj->pin_rx = rx; - - init_uart(obj); - - // For stdio management - if (obj->uart == STDIO_UART) { - stdio_uart_inited = 1; - memcpy(&stdio_uart, obj, sizeof(serial_t)); - } -} - -void serial_free(serial_t *obj) -{ - // Reset UART and disable clock - if (obj->uart == UART_1) { - __USART1_FORCE_RESET(); - __USART1_RELEASE_RESET(); - __USART1_CLK_DISABLE(); - } - if (obj->uart == UART_2) { - __USART2_FORCE_RESET(); - __USART2_RELEASE_RESET(); - __USART2_CLK_DISABLE(); - } - - // Configure GPIOs - pin_function(obj->pin_tx, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)); - pin_function(obj->pin_rx, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)); - - serial_irq_ids[obj->index] = 0; -} - -void serial_baud(serial_t *obj, int baudrate) -{ - obj->baudrate = baudrate; - init_uart(obj); -} - -void serial_format(serial_t *obj, int data_bits, SerialParity parity, int stop_bits) -{ - if (data_bits == 9) { - obj->databits = UART_WORDLENGTH_9B; - } else { - obj->databits = UART_WORDLENGTH_8B; - } - - switch (parity) { - case ParityOdd: - case ParityForced0: - obj->parity = UART_PARITY_ODD; - break; - case ParityEven: - case ParityForced1: - obj->parity = UART_PARITY_EVEN; - break; - default: // ParityNone - obj->parity = UART_PARITY_NONE; - break; - } - - if (stop_bits == 2) { - obj->stopbits = UART_STOPBITS_2; - } else { - obj->stopbits = UART_STOPBITS_1; - } - - init_uart(obj); -} - -/****************************************************************************** - * INTERRUPTS HANDLING - ******************************************************************************/ - -static void uart_irq(UARTName name, int id) -{ - UartHandle.Instance = (USART_TypeDef *)name; - if (serial_irq_ids[id] != 0) { - if (__HAL_UART_GET_FLAG(&UartHandle, UART_FLAG_TC) != RESET) { - irq_handler(serial_irq_ids[id], TxIrq); - __HAL_UART_CLEAR_IT(&UartHandle, UART_FLAG_TC); - } - if (__HAL_UART_GET_FLAG(&UartHandle, UART_FLAG_RXNE) != RESET) { - irq_handler(serial_irq_ids[id], RxIrq); - volatile uint32_t tmpval = UartHandle.Instance->RDR; // Clear RXNE bit - } - } -} - -static void uart1_irq(void) -{ - uart_irq(UART_1, 0); -} - -static void uart2_irq(void) -{ - uart_irq(UART_2, 1); -} - -void serial_irq_handler(serial_t *obj, uart_irq_handler handler, uint32_t id) -{ - irq_handler = handler; - serial_irq_ids[obj->index] = id; -} - -void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) -{ - IRQn_Type irq_n = (IRQn_Type)0; - uint32_t vector = 0; - - UartHandle.Instance = (USART_TypeDef *)(obj->uart); - - if (obj->uart == UART_1) { - irq_n = USART1_IRQn; - vector = (uint32_t)&uart1_irq; - } - - if (obj->uart == UART_2) { - irq_n = USART2_IRQn; - vector = (uint32_t)&uart2_irq; - } - - if (enable) { - - if (irq == RxIrq) { - __HAL_UART_ENABLE_IT(&UartHandle, UART_IT_RXNE); - } else { // TxIrq - __HAL_UART_ENABLE_IT(&UartHandle, UART_IT_TC); - } - - NVIC_SetVector(irq_n, vector); - NVIC_EnableIRQ(irq_n); - - } else { // disable - - int all_disabled = 0; - - if (irq == RxIrq) { - __HAL_UART_DISABLE_IT(&UartHandle, UART_IT_RXNE); - // Check if TxIrq is disabled too - if ((UartHandle.Instance->CR1 & USART_CR1_TCIE) == 0) all_disabled = 1; - } else { // TxIrq - __HAL_UART_DISABLE_IT(&UartHandle, UART_IT_TC); - // Check if RxIrq is disabled too - if ((UartHandle.Instance->CR1 & USART_CR1_RXNEIE) == 0) all_disabled = 1; - } - - if (all_disabled) NVIC_DisableIRQ(irq_n); - - } -} - -/****************************************************************************** - * READ/WRITE - ******************************************************************************/ - -int serial_getc(serial_t *obj) -{ - USART_TypeDef *uart = (USART_TypeDef *)(obj->uart); - while (!serial_readable(obj)); - return (int)(uart->RDR & (uint16_t)0xFF); -} - -void serial_putc(serial_t *obj, int c) -{ - USART_TypeDef *uart = (USART_TypeDef *)(obj->uart); - while (!serial_writable(obj)); - uart->TDR = (uint32_t)(c & (uint16_t)0xFF); -} - -int serial_readable(serial_t *obj) -{ - int status; - UartHandle.Instance = (USART_TypeDef *)(obj->uart); - // Check if data is received - status = ((__HAL_UART_GET_FLAG(&UartHandle, UART_FLAG_RXNE) != RESET) ? 1 : 0); - return status; -} - -int serial_writable(serial_t *obj) -{ - int status; - UartHandle.Instance = (USART_TypeDef *)(obj->uart); - // Check if data is transmitted - status = ((__HAL_UART_GET_FLAG(&UartHandle, UART_FLAG_TXE) != RESET) ? 1 : 0); - return status; -} - -void serial_clear(serial_t *obj) -{ - UartHandle.Instance = (USART_TypeDef *)(obj->uart); - __HAL_UART_CLEAR_IT(&UartHandle, UART_FLAG_TC); - __HAL_UART_SEND_REQ(&UartHandle, UART_RXDATA_FLUSH_REQUEST); -} - -void serial_pinout_tx(PinName tx) -{ - pinmap_pinout(tx, PinMap_UART_TX); -} - -void serial_break_set(serial_t *obj) -{ - // [TODO] -} - -void serial_break_clear(serial_t *obj) -{ - // [TODO] -} - -#endif diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/sleep.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/sleep.c deleted file mode 100644 index 723a5751be..0000000000 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/sleep.c +++ /dev/null @@ -1,59 +0,0 @@ -/* mbed Microcontroller Library - ******************************************************************************* - * Copyright (c) 2014, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - ******************************************************************************* - */ -#include "sleep_api.h" - -#if DEVICE_SLEEP - -#include "cmsis.h" - -void sleep(void) -{ - // Stop HAL systick - HAL_SuspendTick(); - // Request to enter SLEEP mode - HAL_PWR_EnterSLEEPMode(PWR_MAINREGULATOR_ON, PWR_SLEEPENTRY_WFI); - // Restart HAL systick - HAL_ResumeTick(); -} - -void deepsleep(void) -{ - // Request to enter STOP mode with regulator in low power mode - HAL_PWR_EnterSTOPMode(PWR_LOWPOWERREGULATOR_ON, PWR_STOPENTRY_WFI); - - HAL_InitTick(TICK_INT_PRIORITY); - - // After wake-up from STOP reconfigure the PLL - SetSysClock(); - - HAL_InitTick(TICK_INT_PRIORITY); -} - -#endif diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/spi_api.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/spi_api.c deleted file mode 100644 index 3aee1ff2ab..0000000000 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/spi_api.c +++ /dev/null @@ -1,297 +0,0 @@ -/* mbed Microcontroller Library - ******************************************************************************* - * Copyright (c) 2014, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - ******************************************************************************* - */ -#include "mbed_assert.h" -#include "spi_api.h" - -#if DEVICE_SPI - -#include -#include "cmsis.h" -#include "pinmap.h" -#include "PeripheralPins.h" - -static SPI_HandleTypeDef SpiHandle; - -static void init_spi(spi_t *obj) -{ - SpiHandle.Instance = (SPI_TypeDef *)(obj->spi); - - __HAL_SPI_DISABLE(&SpiHandle); - - SpiHandle.Init.Mode = obj->mode; - SpiHandle.Init.BaudRatePrescaler = obj->br_presc; - SpiHandle.Init.Direction = SPI_DIRECTION_2LINES; - SpiHandle.Init.CLKPhase = obj->cpha; - SpiHandle.Init.CLKPolarity = obj->cpol; - SpiHandle.Init.CRCCalculation = SPI_CRCCALCULATION_DISABLED; - SpiHandle.Init.CRCPolynomial = 7; - SpiHandle.Init.DataSize = obj->bits; - SpiHandle.Init.FirstBit = SPI_FIRSTBIT_MSB; - SpiHandle.Init.NSS = obj->nss; - SpiHandle.Init.TIMode = SPI_TIMODE_DISABLED; - - HAL_SPI_Init(&SpiHandle); - - __HAL_SPI_ENABLE(&SpiHandle); -} - -void spi_init(spi_t *obj, PinName mosi, PinName miso, PinName sclk, PinName ssel) -{ - // Determine the SPI to use - SPIName spi_mosi = (SPIName)pinmap_peripheral(mosi, PinMap_SPI_MOSI); - SPIName spi_miso = (SPIName)pinmap_peripheral(miso, PinMap_SPI_MISO); - SPIName spi_sclk = (SPIName)pinmap_peripheral(sclk, PinMap_SPI_SCLK); - SPIName spi_ssel = (SPIName)pinmap_peripheral(ssel, PinMap_SPI_SSEL); - - SPIName spi_data = (SPIName)pinmap_merge(spi_mosi, spi_miso); - SPIName spi_cntl = (SPIName)pinmap_merge(spi_sclk, spi_ssel); - - obj->spi = (SPIName)pinmap_merge(spi_data, spi_cntl); - MBED_ASSERT(obj->spi != (SPIName)NC); - - // Enable SPI clock - if (obj->spi == SPI_1) { - __SPI1_CLK_ENABLE(); - } - if (obj->spi == SPI_2) { - __SPI2_CLK_ENABLE(); - } - - // Configure the SPI pins - pinmap_pinout(mosi, PinMap_SPI_MOSI); - pinmap_pinout(miso, PinMap_SPI_MISO); - pinmap_pinout(sclk, PinMap_SPI_SCLK); - - // Save new values - obj->bits = SPI_DATASIZE_8BIT; - obj->cpol = SPI_POLARITY_LOW; - obj->cpha = SPI_PHASE_1EDGE; - obj->br_presc = SPI_BAUDRATEPRESCALER_256; - - obj->pin_miso = miso; - obj->pin_mosi = mosi; - obj->pin_sclk = sclk; - obj->pin_ssel = ssel; - - if (ssel == NC) { // SW NSS Master mode - obj->mode = SPI_MODE_MASTER; - obj->nss = SPI_NSS_SOFT; - } else { // Slave - pinmap_pinout(ssel, PinMap_SPI_SSEL); - obj->mode = SPI_MODE_SLAVE; - obj->nss = SPI_NSS_HARD_INPUT; - } - - init_spi(obj); -} - -void spi_free(spi_t *obj) -{ - // Reset SPI and disable clock - if (obj->spi == SPI_1) { - __SPI1_FORCE_RESET(); - __SPI1_RELEASE_RESET(); - __SPI1_CLK_DISABLE(); - } - - if (obj->spi == SPI_2) { - __SPI2_FORCE_RESET(); - __SPI2_RELEASE_RESET(); - __SPI2_CLK_DISABLE(); - } - - // Configure GPIOs - pin_function(obj->pin_miso, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)); - pin_function(obj->pin_mosi, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)); - pin_function(obj->pin_sclk, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)); - pin_function(obj->pin_ssel, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, 0)); -} - -void spi_format(spi_t *obj, int bits, int mode, int slave) -{ - // Save new values - if (bits == 16) { - obj->bits = SPI_DATASIZE_16BIT; - } else { - obj->bits = SPI_DATASIZE_8BIT; - } - - switch (mode) { - case 0: - obj->cpol = SPI_POLARITY_LOW; - obj->cpha = SPI_PHASE_1EDGE; - break; - case 1: - obj->cpol = SPI_POLARITY_LOW; - obj->cpha = SPI_PHASE_2EDGE; - break; - case 2: - obj->cpol = SPI_POLARITY_HIGH; - obj->cpha = SPI_PHASE_1EDGE; - break; - default: - obj->cpol = SPI_POLARITY_HIGH; - obj->cpha = SPI_PHASE_2EDGE; - break; - } - - if (slave == 0) { - obj->mode = SPI_MODE_MASTER; - obj->nss = SPI_NSS_SOFT; - } else { - obj->mode = SPI_MODE_SLAVE; - obj->nss = SPI_NSS_HARD_INPUT; - } - - init_spi(obj); -} - -void spi_frequency(spi_t *obj, int hz) -{ - // Note: The frequencies are obtained with SPI clock = 48 MHz (APB clock) - if (hz < 375000) { - obj->br_presc = SPI_BAUDRATEPRESCALER_256; // 188 kHz - } else if ((hz >= 375000) && (hz < 750000)) { - obj->br_presc = SPI_BAUDRATEPRESCALER_128; // 375 kHz - } else if ((hz >= 750000) && (hz < 1000000)) { - obj->br_presc = SPI_BAUDRATEPRESCALER_64; // 750 kHz - } else if ((hz >= 1000000) && (hz < 3000000)) { - obj->br_presc = SPI_BAUDRATEPRESCALER_32; // 1.5 MHz - } else if ((hz >= 3000000) && (hz < 6000000)) { - obj->br_presc = SPI_BAUDRATEPRESCALER_16; // 3 MHz - } else if ((hz >= 6000000) && (hz < 12000000)) { - obj->br_presc = SPI_BAUDRATEPRESCALER_8; // 6 MHz - } else if ((hz >= 12000000) && (hz < 24000000)) { - obj->br_presc = SPI_BAUDRATEPRESCALER_4; // 12 MHz - } else { // >= 24000000 - obj->br_presc = SPI_BAUDRATEPRESCALER_2; // 24 MHz - } - init_spi(obj); -} - -static inline int ssp_readable(spi_t *obj) -{ - int status; - SpiHandle.Instance = (SPI_TypeDef *)(obj->spi); - // Check if data is received - status = ((__HAL_SPI_GET_FLAG(&SpiHandle, SPI_FLAG_RXNE) != RESET) ? 1 : 0); - return status; -} - -static inline int ssp_writeable(spi_t *obj) -{ - int status; - SpiHandle.Instance = (SPI_TypeDef *)(obj->spi); - // Check if data is transmitted - status = ((__HAL_SPI_GET_FLAG(&SpiHandle, SPI_FLAG_TXE) != RESET) ? 1 : 0); - return status; -} - -static inline void ssp_write(spi_t *obj, int value) -{ - SPI_TypeDef *spi = (SPI_TypeDef *)(obj->spi); - while (!ssp_writeable(obj)); - if (obj->bits == SPI_DATASIZE_8BIT) { - // Force 8-bit access to the data register - uint8_t *p_spi_dr = 0; - p_spi_dr = (uint8_t *) & (spi->DR); - *p_spi_dr = (uint8_t)value; - } else { // SPI_DATASIZE_16BIT - spi->DR = (uint16_t)value; - } -} - -static inline int ssp_read(spi_t *obj) -{ - SPI_TypeDef *spi = (SPI_TypeDef *)(obj->spi); - while (!ssp_readable(obj)); - if (obj->bits == SPI_DATASIZE_8BIT) { - // Force 8-bit access to the data register - uint8_t *p_spi_dr = 0; - p_spi_dr = (uint8_t *) & (spi->DR); - return (int)(*p_spi_dr); - } else { - return (int)spi->DR; - } -} - -static inline int ssp_busy(spi_t *obj) -{ - int status; - SpiHandle.Instance = (SPI_TypeDef *)(obj->spi); - status = ((__HAL_SPI_GET_FLAG(&SpiHandle, SPI_FLAG_BSY) != RESET) ? 1 : 0); - return status; -} - -int spi_master_write(spi_t *obj, int value) -{ - ssp_write(obj, value); - return ssp_read(obj); -} - -int spi_slave_receive(spi_t *obj) -{ - return ((ssp_readable(obj) && !ssp_busy(obj)) ? 1 : 0); -}; - -int spi_slave_read(spi_t *obj) -{ - SPI_TypeDef *spi = (SPI_TypeDef *)(obj->spi); - while (!ssp_readable(obj)); - if (obj->bits == SPI_DATASIZE_8BIT) { - // Force 8-bit access to the data register - uint8_t *p_spi_dr = 0; - p_spi_dr = (uint8_t *) & (spi->DR); - return (int)(*p_spi_dr); - } else { - return (int)spi->DR; - } -} - -void spi_slave_write(spi_t *obj, int value) -{ - SPI_TypeDef *spi = (SPI_TypeDef *)(obj->spi); - while (!ssp_writeable(obj)); - if (obj->bits == SPI_DATASIZE_8BIT) { - // Force 8-bit access to the data register - uint8_t *p_spi_dr = 0; - p_spi_dr = (uint8_t *) & (spi->DR); - *p_spi_dr = (uint8_t)value; - } else { // SPI_DATASIZE_16BIT - spi->DR = (uint16_t)value; - } -} - -int spi_busy(spi_t *obj) -{ - return ssp_busy(obj); -} - -#endif diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/us_ticker.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/us_ticker.c deleted file mode 100644 index 01180361ae..0000000000 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/us_ticker.c +++ /dev/null @@ -1,179 +0,0 @@ -/* mbed Microcontroller Library - * Copyright (c) 2014, STMicroelectronics - * All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions are met: - * - * 1. Redistributions of source code must retain the above copyright notice, - * this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright notice, - * this list of conditions and the following disclaimer in the documentation - * and/or other materials provided with the distribution. - * 3. Neither the name of STMicroelectronics nor the names of its contributors - * may be used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" - * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE - * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE - * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE - * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL - * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR - * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER - * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, - * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE - * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. - */ -#include -#include "us_ticker_api.h" -#include "PeripheralNames.h" - -// Timer selection: -#define TIM_MST TIM1 -#define TIM_MST_UP_IRQ TIM1_BRK_UP_TRG_COM_IRQn -#define TIM_MST_OC_IRQ TIM1_CC_IRQn -#define TIM_MST_RCC __TIM1_CLK_ENABLE() - -static TIM_HandleTypeDef TimMasterHandle; - - -static int us_ticker_inited = 0; -static volatile uint32_t SlaveCounter = 0; -static volatile uint32_t oc_int_part = 0; -static volatile uint16_t oc_rem_part = 0; - -void set_compare(uint16_t count) -{ - TimMasterHandle.Instance = TIM_MST; - - // Set new output compare value - __HAL_TIM_SetCompare(&TimMasterHandle, TIM_CHANNEL_1, count); - // Enable IT - __HAL_TIM_ENABLE_IT(&TimMasterHandle, TIM_IT_CC1); -} - -// Used to increment the slave counter -static void tim_update_irq_handler(void) -{ - TimMasterHandle.Instance = TIM_MST; - - // Clear Update interrupt flag - if (__HAL_TIM_GET_FLAG(&TimMasterHandle, TIM_FLAG_UPDATE) == SET) { - __HAL_TIM_CLEAR_FLAG(&TimMasterHandle, TIM_FLAG_UPDATE); - SlaveCounter++; - } -} - -// Used by interrupt system -static void tim_oc_irq_handler(void) -{ - uint16_t cval = TIM_MST->CNT; - TimMasterHandle.Instance = TIM_MST; - - // Clear CC1 interrupt flag - if (__HAL_TIM_GET_FLAG(&TimMasterHandle, TIM_FLAG_CC1) == SET) { - __HAL_TIM_CLEAR_FLAG(&TimMasterHandle, TIM_FLAG_CC1); - } - - if (oc_rem_part > 0) { - set_compare(oc_rem_part); // Finish the remaining time left - oc_rem_part = 0; - } else { - if (oc_int_part > 0) { - set_compare(0xFFFF); - oc_rem_part = cval; // To finish the counter loop the next time - oc_int_part--; - } else { - us_ticker_irq_handler(); - } - } -} - -void us_ticker_init(void) -{ - - if (us_ticker_inited) return; - us_ticker_inited = 1; - - // Enable timer clock - TIM_MST_RCC; - - // Configure time base - TimMasterHandle.Instance = TIM_MST; - TimMasterHandle.Init.Period = 0xFFFF; - TimMasterHandle.Init.Prescaler = (uint32_t)(SystemCoreClock / 1000000) - 1; // 1 �s tick - TimMasterHandle.Init.ClockDivision = 0; - TimMasterHandle.Init.CounterMode = TIM_COUNTERMODE_UP; - HAL_TIM_Base_Init(&TimMasterHandle); - - // Configure interrupts - __HAL_TIM_ENABLE_IT(&TimMasterHandle, TIM_IT_UPDATE); - - // Update interrupt used for 32-bit counter - NVIC_SetVector(TIM_MST_UP_IRQ, (uint32_t)tim_update_irq_handler); - NVIC_EnableIRQ(TIM_MST_UP_IRQ); - - // Output compare interrupt used for timeout feature - NVIC_SetVector(TIM_MST_OC_IRQ, (uint32_t)tim_oc_irq_handler); - NVIC_EnableIRQ(TIM_MST_OC_IRQ); - - // Enable timer - HAL_TIM_Base_Start(&TimMasterHandle); -} - -uint32_t us_ticker_read() -{ - uint32_t counter, counter2; - if (!us_ticker_inited) us_ticker_init(); - // A situation might appear when Master overflows right after Slave is read and before the - // new (overflowed) value of Master is read. Which would make the code below consider the - // previous (incorrect) value of Slave and the new value of Master, which would return a - // value in the past. Avoid this by computing consecutive values of the timer until they - // are properly ordered. - counter = (uint32_t)(SlaveCounter << 16); - counter += TIM_MST->CNT; - while (1) { - counter2 = (uint32_t)(SlaveCounter << 16); - counter2 += TIM_MST->CNT; - if (counter2 > counter) { - break; - } - counter = counter2; - } - return counter2; -} - -void us_ticker_set_interrupt(timestamp_t timestamp) -{ - int delta = (int)((uint32_t)timestamp - us_ticker_read()); - uint16_t cval = TIM_MST->CNT; - - if (delta <= 0) { // This event was in the past - us_ticker_irq_handler(); - } else { - oc_int_part = (uint32_t)(delta >> 16); - oc_rem_part = (uint16_t)(delta & 0xFFFF); - if (oc_rem_part <= (0xFFFF - cval)) { - set_compare(cval + oc_rem_part); - oc_rem_part = 0; - } else { - set_compare(0xFFFF); - oc_rem_part = oc_rem_part - (0xFFFF - cval); - } - } -} - -void us_ticker_disable_interrupt(void) -{ - TimMasterHandle.Instance = TIM_MST; - __HAL_TIM_DISABLE_IT(&TimMasterHandle, TIM_IT_CC1); -} - -void us_ticker_clear_interrupt(void) -{ - TimMasterHandle.Instance = TIM_MST; - if (__HAL_TIM_GET_FLAG(&TimMasterHandle, TIM_FLAG_CC1) == SET) { - __HAL_TIM_CLEAR_FLAG(&TimMasterHandle, TIM_FLAG_CC1); - } -} diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/PeripheralNames.h b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/TARGET_DISCO_F051R8/PeripheralNames.h similarity index 96% rename from libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/PeripheralNames.h rename to libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/TARGET_DISCO_F051R8/PeripheralNames.h index f18c4775e0..cd7c25c8c0 100644 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/PeripheralNames.h +++ b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/TARGET_DISCO_F051R8/PeripheralNames.h @@ -65,7 +65,9 @@ typedef enum { } I2CName; typedef enum { - PWM_3 = (int)TIM3_BASE, + PWM_1 = (int)TIM1_BASE, + PWM_2 = (int)TIM2_BASE, + PWM_3 = (int)TIM3_BASE, PWM_14 = (int)TIM14_BASE, PWM_15 = (int)TIM15_BASE, PWM_16 = (int)TIM16_BASE, diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/PeripheralPins.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/TARGET_DISCO_F051R8/PeripheralPins.c similarity index 100% rename from libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/PeripheralPins.c rename to libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/TARGET_DISCO_F051R8/PeripheralPins.c diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/PinNames.h b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/TARGET_DISCO_F051R8/PinNames.h similarity index 100% rename from libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/PinNames.h rename to libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/TARGET_DISCO_F051R8/PinNames.h diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/PortNames.h b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/TARGET_DISCO_F051R8/PortNames.h similarity index 100% rename from libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/PortNames.h rename to libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/TARGET_DISCO_F051R8/PortNames.h diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/device.h b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/TARGET_DISCO_F051R8/device.h similarity index 100% rename from libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/device.h rename to libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/TARGET_DISCO_F051R8/device.h diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/objects.h b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/TARGET_DISCO_F051R8/objects.h similarity index 100% rename from libraries/mbed/targets/hal/TARGET_STM/TARGET_DISCO_F051R8/objects.h rename to libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/TARGET_DISCO_F051R8/objects.h diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/pwmout_api.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/pwmout_api.c index 477f02b353..463bb72445 100644 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/pwmout_api.c +++ b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/pwmout_api.c @@ -101,7 +101,7 @@ void pwmout_write(pwmout_t* obj, float value) sConfig.OCIdleState = TIM_OCIDLESTATE_RESET; sConfig.OCNIdleState = TIM_OCNIDLESTATE_RESET; -#if defined (TARGET_STM32F030R8) +#if defined (TARGET_STM32F030R8) || defined (TARGET_STM32F051R8) switch (obj->pin) { // Channels 1 case PA_4: diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/serial_api.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/serial_api.c index 5561db21d1..d8bd3495a0 100644 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/serial_api.c +++ b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/serial_api.c @@ -42,7 +42,7 @@ static uint32_t serial_irq_ids[UART_NUM] = {0, 0, 0, 0, 0, 0, 0, 0}; -#elif defined (TARGET_STM32F030R8) +#elif defined (TARGET_STM32F030R8) || defined (TARGET_STM32F051R8) #define UART_NUM (2) static uint32_t serial_irq_ids[UART_NUM] = {0, 0}; @@ -410,7 +410,7 @@ void serial_irq_set(serial_t *obj, SerialIrq irq, uint32_t enable) vector = (uint32_t)&uart8_irq; } -#elif defined (TARGET_STM32F030R8) +#elif defined (TARGET_STM32F030R8) || defined (TARGET_STM32F051R8) #else if (obj->uart == UART_3) { diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/sleep.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/sleep.c index c128621a8f..8ae2f12334 100644 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/sleep.c +++ b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/sleep.c @@ -50,7 +50,7 @@ void sleep(void) __HAL_TIM_ENABLE_IT(&TimMasterHandle, (TIM_IT_CC2 | TIM_IT_UPDATE)); } -#elif defined(TARGET_STM32F030R8) +#elif defined(TARGET_STM32F030R8) || defined (TARGET_STM32F051R8) void sleep(void) { // Stop HAL systick @@ -79,7 +79,7 @@ void sleep(void) } #endif -#if defined(TARGET_STM32F030R8) +#if defined(TARGET_STM32F030R8) || defined (TARGET_STM32F051R8) void deepsleep(void) { // Request to enter STOP mode with regulator in low power mode diff --git a/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/us_ticker.c b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/us_ticker.c index 5ac33b4039..01f2ec8251 100644 --- a/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/us_ticker.c +++ b/libraries/mbed/targets/hal/TARGET_STM/TARGET_STM32F0/us_ticker.c @@ -114,7 +114,7 @@ void us_ticker_clear_interrupt(void) } } -#elif defined(TARGET_STM32F030R8) +#elif defined(TARGET_STM32F030R8) || defined (TARGET_STM32F051R8) // Timer selection: #define TIM_MST TIM1