aboutsummaryrefslogtreecommitdiff
path: root/lib
diff options
context:
space:
mode:
Diffstat (limited to 'lib')
-rw-r--r--lib/dispatch/vector_nvic.c2
-rw-r--r--lib/stm32/can.c172
-rw-r--r--lib/stm32/common/gpio_common_all.c139
-rw-r--r--lib/stm32/common/gpio_common_f24.c195
-rw-r--r--lib/stm32/desig.c (renamed from lib/stm32/f1/desig.c)24
-rw-r--r--lib/stm32/exti2.c (renamed from lib/stm32/f4/exti.c)20
-rw-r--r--lib/stm32/f1/Makefile5
-rw-r--r--lib/stm32/f1/adc.c114
-rw-r--r--lib/stm32/f1/dma.c11
-rw-r--r--lib/stm32/f1/gpio.c142
-rw-r--r--lib/stm32/f1/rcc.c167
-rw-r--r--lib/stm32/f1/rtc.c2
-rw-r--r--lib/stm32/f2/Makefile5
-rw-r--r--lib/stm32/f2/exti.c146
-rw-r--r--lib/stm32/f2/gpio.c134
-rw-r--r--lib/stm32/f4/Makefile7
-rw-r--r--lib/stm32/f4/gpio.c134
-rw-r--r--lib/stm32/i2c.c144
-rw-r--r--lib/stm32/l1/Makefile37
-rw-r--r--lib/stm32/l1/gpio.c28
-rw-r--r--lib/stm32/l1/libopencm3_stm32l1.ld83
-rw-r--r--lib/stm32/l1/rcc.c357
-rw-r--r--lib/stm32/l1/stm32l15xx8.ld31
-rw-r--r--lib/stm32/l1/stm32l15xxb.ld31
-rw-r--r--lib/stm32/usart.c2
-rw-r--r--lib/usb/usb.c3
-rw-r--r--lib/usb/usb_control.c5
-rw-r--r--lib/usb/usb_private.h1
-rw-r--r--lib/usb/usb_standard.c73
29 files changed, 1584 insertions, 630 deletions
diff --git a/lib/dispatch/vector_nvic.c b/lib/dispatch/vector_nvic.c
index b8e9b7f..33104eb 100644
--- a/lib/dispatch/vector_nvic.c
+++ b/lib/dispatch/vector_nvic.c
@@ -4,6 +4,8 @@
# include "../stm32/f2/vector_nvic.c"
#elif defined(STM32F4)
# include "../stm32/f4/vector_nvic.c"
+#elif defined(STM32L1)
+# include "../stm32/l1/vector_nvic.c"
#elif defined(EFM32TG)
# include "../efm32/efm32tg/vector_nvic.c"
diff --git a/lib/stm32/can.c b/lib/stm32/can.c
index 73036f4..7fde585 100644
--- a/lib/stm32/can.c
+++ b/lib/stm32/can.c
@@ -1,3 +1,21 @@
+/** @defgroup can_file CAN
+
+@ingroup STM32F_files
+
+@brief <b>libopencm3 STM32Fxxx CAN</b>
+
+@version 1.0.0
+
+@author @htmlonly &copy; @endhtmlonly 2010 Piotr Esden-Tempski <piotr@esden.net>
+
+@date 12 November 2012
+
+Devices can have up to two CAN peripherals. The peripherals support up to 1MBit
+transmission rate. The peripheral has several filters for incoming messages that
+can be distributed between two FIFOs and three transmit mailboxes.
+
+LGPL License Terms @ref lgpl_license
+*/
/*
* This file is part of the libopencm3 project.
*
@@ -29,6 +47,14 @@
# error "stm32 family not defined."
#endif
+/*-----------------------------------------------------------------------------*/
+/** @brief CAN Reset
+
+The CAN peripheral and all its associated configuration registers are placed in the
+reset condition. The reset is effective via the RCC peripheral reset system.
+
+@param[in] canport Unsigned int32. CAN block register address base @ref can_reg_base.
+ */
void can_reset(u32 canport)
{
if (canport == CAN1) {
@@ -40,8 +66,27 @@ void can_reset(u32 canport)
}
}
+/*-----------------------------------------------------------------------------*/
+/** @brief CAN Init
+
+Initialize the selected CAN peripheral block.
+
+@param[in] canport Unsigend int32. CAN register base address @ref can_reg_base.
+@param[in] ttcm bool. Time triggered communication mode.
+@param[in] abom bool. Automatic bus-off management.
+@param[in] awum bool. Automatic wakeup mode.
+@param[in] nart bool. No automatic retransmission.
+@param[in] rflm bool. Receive FIFO locked mode.
+@param[in] txfp bool. Transmit FIFO priority.
+@param[in] sjw Unsigned int32. Resynchronization time quanta jump width.
+@param[in] ts1 Unsigned int32. Time segment 1 time quanta width.
+@param[in] ts2 Unsigned int32. Time segment 2 time quanta width.
+@param[in] brp Unsigned int32. Baud rate prescaler.
+@returns int 0 on success, 1 on initialization failure.
+*/
int can_init(u32 canport, bool ttcm, bool abom, bool awum, bool nart,
- bool rflm, bool txfp, u32 sjw, u32 ts1, u32 ts2, u32 brp)
+ bool rflm, bool txfp, u32 sjw, u32 ts1, u32 ts2, u32 brp,
+ bool loopback, bool silent)
{
u32 wait_ack = 0x00000000;
u32 can_msr_inak_timeout = 0x0000FFFF;
@@ -63,6 +108,9 @@ int can_init(u32 canport, bool ttcm, bool abom, bool awum, bool nart,
if ((CAN_MSR(canport) & CAN_MSR_INAK) != CAN_MSR_INAK)
return 1;
+ /* clear can timing bits */
+ CAN_BTR(canport) = 0;
+
/* Set the automatic bus-off management. */
if (ttcm)
CAN_MCR(canport) |= CAN_MCR_TTCM;
@@ -94,8 +142,19 @@ int can_init(u32 canport, bool ttcm, bool abom, bool awum, bool nart,
else
CAN_MCR(canport) &= ~CAN_MCR_TXFP;
+ if (silent)
+ CAN_BTR(canport) |= CAN_BTR_SILM;
+ else
+ CAN_BTR(canport) &= ~CAN_BTR_SILM;
+
+ if (loopback)
+ CAN_BTR(canport) |= CAN_BTR_LBKM;
+ else
+ CAN_BTR(canport) &= ~CAN_BTR_LBKM;
+
+
/* Set bit timings. */
- CAN_BTR(canport) = sjw | ts2 | ts1 |
+ CAN_BTR(canport) |= sjw | ts2 | ts1 |
(u32)(CAN_BTR_BRP_MASK & (brp - 1));
/* Request initialization "leave". */
@@ -114,6 +173,20 @@ int can_init(u32 canport, bool ttcm, bool abom, bool awum, bool nart,
return ret;
}
+/*-----------------------------------------------------------------------------*/
+/** @brief CAN Filter Init
+
+Initialize incoming message filter and assign to FIFO.
+
+@param[in] canport Unsigned int32. CAN block register base @ref can_reg_base.
+@param[in] nr Unsigned int32. ID number of the filter.
+@param[in] scale_32bit bool. 32-bit scale for the filter?
+@param[in] id_list_mode bool. ID list filter mode?
+@param[in] fr1 Unsigned int32. First filter register content.
+@param[in] fr2 Unsigned int32. Second filter register content.
+@param[in] fifo Unsigned int32. FIFO id.
+@param[in] enable bool. Enable filter?
+ */
void can_filter_init(u32 canport, u32 nr, bool scale_32bit, bool id_list_mode,
u32 fr1, u32 fr2, u32 fifo, bool enable)
{
@@ -160,6 +233,18 @@ void can_filter_init(u32 canport, u32 nr, bool scale_32bit, bool id_list_mode,
CAN_FMR(canport) &= ~CAN_FMR_FINIT;
}
+/*-----------------------------------------------------------------------------*/
+/** @brief CAN Initialize a 16bit Message ID Mask Filter
+
+@param[in] canport Unsigned int32. CAN block register base @ref can_reg_base.
+@param[in] nr Unsigned int32. ID number of the filter.
+@param[in] id1 Unsigned int16. First message ID to filter.
+@param[in] mask1 Unsigned int16. First message ID bit mask.
+@param[in] id2 Unsigned int16. Second message ID to filter.
+@param[in] mask2 Unsigned int16. Second message ID bit mask.
+@param[in] fifo Unsigned int32. FIFO id.
+@param[in] enable bool. Enable filter?
+ */
void can_filter_id_mask_16bit_init(u32 canport, u32 nr, u16 id1, u16 mask1,
u16 id2, u16 mask2, u32 fifo, bool enable)
{
@@ -168,12 +253,34 @@ void can_filter_id_mask_16bit_init(u32 canport, u32 nr, u16 id1, u16 mask1,
((u32)id2 << 16) | (u32)mask2, fifo, enable);
}
+/*-----------------------------------------------------------------------------*/
+/** @brief CAN Initialize a 32bit Message ID Mask Filter
+
+@param[in] canport Unsigned int32. CAN block register base @ref can_reg_base.
+@param[in] nr Unsigned int32. ID number of the filter.
+@param[in] id Unsigned int32. Message ID to filter.
+@param[in] mask Unsigned int32. Message ID bit mask.
+@param[in] fifo Unsigned int32. FIFO id.
+@param[in] enable bool. Enable filter?
+ */
void can_filter_id_mask_32bit_init(u32 canport, u32 nr, u32 id, u32 mask,
u32 fifo, bool enable)
{
can_filter_init(canport, nr, true, false, id, mask, fifo, enable);
}
+/*-----------------------------------------------------------------------------*/
+/** @brief CAN Initialize a 16bit Message ID List Filter
+
+@param[in] canport Unsigned int32. CAN block register base @ref can_reg_base.
+@param[in] nr Unsigned int32. ID number of the filter.
+@param[in] id1 Unsigned int16. First message ID to match.
+@param[in] id2 Unsigned int16. Second message ID to match.
+@param[in] id3 Unsigned int16. Third message ID to match.
+@param[in] id4 Unsigned int16. Fourth message ID to match.
+@param[in] fifo Unsigned int32. FIFO id.
+@param[in] enable bool. Enable filter?
+ */
void can_filter_id_list_16bit_init(u32 canport, u32 nr, u16 id1, u16 id2,
u16 id3, u16 id4, u32 fifo, bool enable)
{
@@ -182,27 +289,62 @@ void can_filter_id_list_16bit_init(u32 canport, u32 nr, u16 id1, u16 id2,
((u32)id3 << 16) | (u32)id4, fifo, enable);
}
+/*-----------------------------------------------------------------------------*/
+/** @brief CAN Initialize a 32bit Message ID List Filter
+
+@param[in] canport Unsigned int32. CAN block register base @ref can_reg_base.
+@param[in] nr Unsigned int32. ID number of the filter.
+@param[in] id1 Unsigned int32. First message ID to match.
+@param[in] id2 Unsigned int32. Second message ID to match.
+@param[in] fifo Unsigned int32. FIFO id.
+@param[in] enable bool. Enable filter?
+ */
void can_filter_id_list_32bit_init(u32 canport, u32 nr, u32 id1, u32 id2,
u32 fifo, bool enable)
{
can_filter_init(canport, nr, true, true, id1, id2, fifo, enable);
}
+/*-----------------------------------------------------------------------------*/
+/** @brief CAN Enable IRQ
+
+@param[in] canport Unsigned int32. CAN block register base @ref can_reg_base.
+@param[in] irq Unsigned int32. IRQ bit(s).
+ */
void can_enable_irq(u32 canport, u32 irq)
{
CAN_IER(canport) |= irq;
}
+/*-----------------------------------------------------------------------------*/
+/** @brief CAN Disable IRQ
+
+@param[in] canport Unsigned int32. CAN block register base @ref can_reg_base.
+@param[in] irq Unsigned int32. IRQ bit(s).
+ */
void can_disable_irq(u32 canport, u32 irq)
{
CAN_IER(canport) &= ~irq;
}
+/*-----------------------------------------------------------------------------*/
+/** @brief CAN Transmit Message
+
+@param[in] canport Unsigned int32. CAN block register base @ref can_reg_base.
+@param[in] id Unsigned int32. Message ID.
+@param[in] ext bool. Extended message ID?
+@param[in] rtr bool. Request transmit?
+@param[in] length Unsigned int8. Message payload length.
+@param[in] data Unsigned int8[]. Message payload data.
+@returns int 0, 1 or 2 on success and depending on which outgoing mailbox got
+selected. -1 if no mailbox was available and no transmission got queued.
+ */
int can_transmit(u32 canport, u32 id, bool ext, bool rtr, u8 length, u8 *data)
{
int ret = 0, i;
u32 mailbox = 0;
+ /* Check which transmit mailbox is empty if any. */
if ((CAN_TSR(canport) & CAN_TSR_TME0) == CAN_TSR_TME0) {
ret = 0;
mailbox = CAN_MBOX0;
@@ -216,7 +358,7 @@ int can_transmit(u32 canport, u32 id, bool ext, bool rtr, u8 length, u8 *data)
ret = -1;
}
- /* Check if we have an empty mailbox. */
+ /* If we have no empty mailbox return with an error. */
if (ret == -1)
return ret;
@@ -254,6 +396,12 @@ int can_transmit(u32 canport, u32 id, bool ext, bool rtr, u8 length, u8 *data)
return ret;
}
+/*-----------------------------------------------------------------------------*/
+/** @brief CAN Release FIFO
+
+@param[in] canport Unsigned int32. CAN block register base @ref can_reg_base.
+@param[in] fifo Unsigned int8. FIFO id.
+ */
void can_fifo_release(u32 canport, u8 fifo)
{
if (fifo == 0)
@@ -262,6 +410,19 @@ void can_fifo_release(u32 canport, u8 fifo)
CAN_RF1R(canport) |= CAN_RF1R_RFOM1;
}
+/*-----------------------------------------------------------------------------*/
+/** @brief CAN Receive Message
+
+@param[in] canport Unsigned int32. CAN block register base @ref can_reg_base.
+@param[in] fifo Unsigned int8. FIFO id.
+@param[in] release bool. Release the FIFO automatically after coping data out.
+@param[out] id Unsigned int32 pointer. Message ID.
+@param[out] ext bool pointer. The message ID is extended?
+@param[out] rtr bool pointer. Request of transmission?
+@param[out] fmi Unsigned int32 pointer. ID of the matched filter.
+@param[out] length Unsigned int8 pointer. Length of message payload.
+@param[out] data Unsigned int8[]. Message payload data.
+ */
void can_receive(u32 canport, u8 fifo, bool release, u32 *id, bool *ext,
bool *rtr, u32 *fmi, u8 *length, u8 *data)
{
@@ -310,3 +471,8 @@ void can_receive(u32 canport, u8 fifo, bool release, u32 *id, bool *ext,
if (release)
can_fifo_release(canport, fifo);
}
+
+bool can_available_mailbox(u32 canport)
+{
+ return CAN_TSR(canport) & (CAN_TSR_TME0 | CAN_TSR_TME1 | CAN_TSR_TME2);
+}
diff --git a/lib/stm32/common/gpio_common_all.c b/lib/stm32/common/gpio_common_all.c
new file mode 100644
index 0000000..d23e415
--- /dev/null
+++ b/lib/stm32/common/gpio_common_all.c
@@ -0,0 +1,139 @@
+/** @addtogroup gpio_file */
+
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+ *
+ * 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 3 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, see <http://www.gnu.org/licenses/>.
+ */
+
+#define WEAK __attribute__ ((weak))
+
+#include <libopencm3/stm32/gpio.h>
+
+/**@{*/
+
+/*-----------------------------------------------------------------------------*/
+/** @brief Set a Group of Pins Atomic
+
+Set one or more pins of the given GPIO port to 1 in an atomic operation.
+
+@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
+@param[in] gpios Unsigned int16. Pin identifiers @ref gpio_pin_id
+ If multiple pins are to be changed, use logical OR '|' to separate them.
+*/
+void gpio_set(u32 gpioport, u16 gpios)
+{
+ GPIO_BSRR(gpioport) = gpios;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief Clear a Group of Pins Atomic
+
+Clear one or more pins of the given GPIO port to 0 in an atomic operation.
+
+@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
+@param[in] gpios Unsigned int16. Pin identifiers @ref gpio_pin_id
+ If multiple pins are to be changed, use logical OR '|' to separate them.
+*/
+void gpio_clear(u32 gpioport, u16 gpios)
+{
+ GPIO_BSRR(gpioport) = (gpios << 16);
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief Read a Group of Pins.
+
+@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
+@param[in] gpios Unsigned int16. Pin identifiers @ref gpio_pin_id
+ If multiple pins are to be read, use logical OR '|' to separate them.
+@return Unsigned int16 value of the pin values. The bit position of the pin value
+ returned corresponds to the pin number.
+*/
+u16 gpio_get(u32 gpioport, u16 gpios)
+{
+ return gpio_port_read(gpioport) & gpios;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief Toggle a Group of Pins
+
+Toggle one or more pins of the given GPIO port. This is not an atomic operation.
+
+@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
+@param[in] gpios Unsigned int16. Pin identifiers @ref gpio_pin_id
+ If multiple pins are to be changed, use logical OR '|' to separate them.
+*/
+void gpio_toggle(u32 gpioport, u16 gpios)
+{
+ GPIO_ODR(gpioport) ^= gpios;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief Read from a Port
+
+Read the current value of the given GPIO port. Only the lower 16 bits contain
+valid pin data.
+
+@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
+@return Unsigned int16. The value held in the specified GPIO port.
+*/
+u16 gpio_port_read(u32 gpioport)
+{
+ return (u16)GPIO_IDR(gpioport);
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief Write to a Port
+
+Write a value to the given GPIO port.
+
+@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
+@param[in] data Unsigned int16. The value to be written to the GPIO port.
+*/
+void gpio_port_write(u32 gpioport, u16 data)
+{
+ GPIO_ODR(gpioport) = data;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief Lock the Configuration of a Group of Pins
+
+The configuration of one or more pins of the given GPIO port is locked. There is
+no mechanism to unlock these via software. Unlocking occurs at the next reset.
+
+@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
+@param[in] gpios Unsigned int16. Pin identifiers @ref gpio_pin_id
+ If multiple pins are to be locked, use logical OR '|' to separate them.
+*/
+void gpio_port_config_lock(u32 gpioport, u16 gpios)
+{
+ u32 reg32;
+
+ /* Special "Lock Key Writing Sequence", see datasheet. */
+ GPIO_LCKR(gpioport) = GPIO_LCKK | gpios; /* Set LCKK. */
+ GPIO_LCKR(gpioport) = ~GPIO_LCKK & gpios; /* Clear LCKK. */
+ GPIO_LCKR(gpioport) = GPIO_LCKK | gpios; /* Set LCKK. */
+ reg32 = GPIO_LCKR(gpioport); /* Read LCKK. */
+ reg32 = GPIO_LCKR(gpioport); /* Read LCKK again. */
+
+ /* Tell the compiler the variable is actually used. It will get optimized out anyways. */
+ reg32 = reg32;
+
+ /* If (reg32 & GPIO_LCKK) is true, the lock is now active. */
+}
+
+/**@}*/
+
diff --git a/lib/stm32/common/gpio_common_f24.c b/lib/stm32/common/gpio_common_f24.c
new file mode 100644
index 0000000..d464a50
--- /dev/null
+++ b/lib/stm32/common/gpio_common_f24.c
@@ -0,0 +1,195 @@
+/** @addtogroup gpio_file
+
+@version 1.0.0
+
+@author @htmlonly &copy; @endhtmlonly 2009 Uwe Hermann <uwe@hermann-uwe.de>
+@author @htmlonly &copy; @endhtmlonly 2012 Ken Sarkies <ksarkies@internode.on.net>
+
+@date 18 August 2012
+
+Each I/O port has 16 individually configurable bits. Many I/O pins share GPIO
+functionality with a number of alternate functions and must be configured to the
+alternate function mode if these are to be accessed. A feature is available to
+remap alternative functions to a limited set of alternative pins in the event
+of a clash of requirements.
+
+The data registers associated with each port for input and output are 32 bit with
+the upper 16 bits unused. The output buffer must be written as a 32 bit word, but
+individual bits may be set or reset separately in atomic operations to avoid race
+conditions during interrupts. Bits may also be individually locked to prevent
+accidental configuration changes. Once locked the configuration cannot be changed
+until after the next reset.
+
+Each port bit can be configured as analog or digital input, the latter can be
+floating or pulled up or down. As outputs they can be configured as either
+push-pull or open drain, digital I/O or alternate function, and with maximum
+output speeds of 2MHz, 10MHz, or 50MHz.
+
+On reset all ports are configured as digital floating input.
+
+@section gpio_api_ex Basic GPIO Handling API.
+
+Example 1: Push-pull digital output actions with pullup on ports C2 and C9
+
+@code
+ gpio_mode_setup(GPIOC, GPIO_MODE_OUTPUT,
+ GPIO_PUPD_PULLUP, GPIO2 | GPIO9);
+ gpio_output_options(GPIOC, GPIO_OTYPE_PP,
+ GPIO_OSPEED_25MHZ, GPIO2 | GPIO9);
+ gpio_set(GPIOC, GPIO2 | GPIO9);
+ gpio_clear(GPIOC, GPIO2);
+ gpio_toggle(GPIOC, GPIO2 | GPIO9);
+ gpio_port_write(GPIOC, 0x204);
+@endcode
+
+Example 2: Digital input on port C12 with pullup
+
+@code
+ gpio_mode_setup(GPIOC, GPIO_MODE_INPUT,
+ GPIO_PUPD_PULLUP, GPIO12);
+ reg16 = gpio_port_read(GPIOC);
+@endcode
+
+LGPL License Terms @ref lgpl_license
+*/
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2011 Fergus Noble <fergusnoble@gmail.com>
+ *
+ * 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 3 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, see <http://www.gnu.org/licenses/>.
+ */
+
+/**@{*/
+
+#include <libopencm3/stm32/common/gpio_common_all.h>
+#include <libopencm3/stm32/gpio.h>
+
+/*-----------------------------------------------------------------------------*/
+/** @brief Set GPIO Pin Mode
+
+Sets the Pin Direction and Analog/Digital Mode, and Output Pin Pullup,
+for a set of GPIO pins on a given GPIO port.
+
+@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
+@param[in] mode Unsigned int8. Pin mode @ref gpio_mode
+@param[in] pull_up_down Unsigned int8. Pin pullup/pulldown configuration @ref gpio_pup
+@param[in] gpios Unsigned int16. Pin identifiers @ref gpio_pin_id
+ If multiple pins are to be set, use bitwise OR '|' to separate them.
+*/
+void gpio_mode_setup(u32 gpioport, u8 mode, u8 pull_up_down, u16 gpios)
+{
+ u16 i;
+ u32 moder, pupd;
+
+ /*
+ * We want to set the config only for the pins mentioned in gpios,
+ * but keeping the others, so read out the actual config first.
+ */
+ moder = GPIO_MODER(gpioport);
+ pupd = GPIO_PUPDR(gpioport);
+
+ for (i = 0; i < 16; i++) {
+ if (!((1 << i) & gpios))
+ continue;
+
+ moder &= ~GPIO_MODE_MASK(i);
+ moder |= GPIO_MODE(i, mode);
+ pupd &= ~GPIO_PUPD_MASK(i);
+ pupd |= GPIO_PUPD(i, pull_up_down);
+ }
+
+ /* Set mode and pull up/down control registers. */
+ GPIO_MODER(gpioport) = moder;
+ GPIO_PUPDR(gpioport) = pupd;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief Set GPIO Output Options
+
+When the pin is set to output mode, this sets the configuration (analog/digital and
+open drain/push pull) and speed, for a set of GPIO pins on a given GPIO port.
+
+@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
+@param[in] otype Unsigned int8. Pin output type @ref gpio_output_type
+@param[in] speed Unsigned int8. Pin speed @ref gpio_speed
+@param[in] gpios Unsigned int16. Pin identifiers @ref gpio_pin_id
+ If multiple pins are to be set, use bitwise OR '|' to separate them.
+*/
+void gpio_set_output_options(u32 gpioport, u8 otype, u8 speed, u16 gpios)
+{
+ u16 i;
+ u32 ospeedr;
+
+ if (otype == 0x1)
+ GPIO_OTYPER(gpioport) |= gpios;
+ else
+ GPIO_OTYPER(gpioport) &= ~gpios;
+
+ ospeedr = GPIO_OSPEEDR(gpioport);
+
+ for (i = 0; i < 16; i++) {
+ if (!((1 << i) & gpios))
+ continue;
+ ospeedr &= ~GPIO_OSPEED_MASK(i);
+ ospeedr |= GPIO_OSPEED(i, speed);
+ }
+
+ GPIO_OSPEEDR(gpioport) = ospeedr;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief Set GPIO Alternate Function Selection
+
+Set the alternate function mapping number for each pin. Most pins have alternate
+functions associated with them. When set to AF mode, a pin may be used for one of
+its allocated alternate functions selected by the number given here. To determine
+the number to be used for the desired function refer to the individual datasheet
+for the particular device. A table is given under the Pin Selection chapter.
+
+Note that a number of pins may be set but only with a single AF number. In practice
+this would rarely be useful as each pin is likely to require a different number.
+
+@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
+@param[in] alt_func_num Unsigned int8. Pin alternate function number @ref gpio_af_num
+@param[in] gpios Unsigned int16. Pin identifiers @ref gpio_pin_id
+ If multiple pins are to be set, use bitwise OR '|' to separate them.
+*/
+void gpio_set_af(u32 gpioport, u8 alt_func_num, u16 gpios)
+{
+ u16 i;
+ u32 afrl, afrh;
+
+ afrl = GPIO_AFRL(gpioport);
+ afrh = GPIO_AFRH(gpioport);
+
+ for (i = 0; i < 8; i++) {
+ if (!((1 << i) & gpios))
+ continue;
+ afrl &= ~GPIO_AFR_MASK(i);
+ afrl |= GPIO_AFR(i, alt_func_num);
+ }
+
+ for (i = 8; i < 16; i++) {
+ if (!((1 << i) & gpios))
+ continue;
+ afrl &= ~GPIO_AFR_MASK(i - 8);
+ afrh |= GPIO_AFR(i - 8, alt_func_num);
+ }
+
+ GPIO_AFRL(gpioport) = afrl;
+ GPIO_AFRH(gpioport) = afrh;
+}
+/**@}*/
+
diff --git a/lib/stm32/f1/desig.c b/lib/stm32/desig.c
index 7ae968e..ea861aa 100644
--- a/lib/stm32/f1/desig.c
+++ b/lib/stm32/desig.c
@@ -17,7 +17,7 @@
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
-#include <libopencm3/stm32/f1/desig.h>
+#include <libopencm3/stm32/desig.h>
u16 desig_get_flash_size(void)
{
@@ -35,3 +35,25 @@ void desig_get_unique_id(u32 result[])
result[1] = bits63_32;
result[2] = bits31_16 << 16 | bits15_0;
}
+
+void desig_get_unique_id_as_string(char *string,
+ unsigned int string_len)
+{
+ int i, len;
+ u8 device_id[12];
+ static const char chars[] = "0123456789ABCDEF";
+
+ desig_get_unique_id((u32 *)device_id);
+
+ /* Each byte produces two characters */
+ len = (2 * sizeof(device_id) < string_len) ?
+ 2 * sizeof(device_id) : string_len - 1;
+
+ for (i = 0; i < len; i += 2) {
+ string[i] = chars[(device_id[i / 2] >> 0) & 0x0F];
+ string[i + 1] = chars[(device_id[i / 2] >> 4) & 0x0F];
+ }
+
+ string[len] = '\0';
+}
+
diff --git a/lib/stm32/f4/exti.c b/lib/stm32/exti2.c
index f69e99e..bea2f4d 100644
--- a/lib/stm32/f4/exti.c
+++ b/lib/stm32/exti2.c
@@ -2,6 +2,7 @@
* This file is part of the libopencm3 project.
*
* Copyright (C) 2010 Mark Butler <mbutler@physics.otago.ac.nz>
+ * Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
*
* 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
@@ -15,11 +16,22 @@
*
* You should have received a copy of the GNU Lesser General Public License
* along with this library. If not, see <http://www.gnu.org/licenses/>.
+ *
+ * This provides the code for the "next gen" EXTI block provided in F2/F4/L1
+ * devices. (differences only in the source selection)
*/
#include <libopencm3/stm32/exti.h>
-#include <libopencm3/stm32/f4/syscfg.h>
+#include <libopencm3/stm32/syscfg.h>
+#if defined(STM32F2)
+#include <libopencm3/stm32/f2/gpio.h>
+#elif defined(STM32F4)
#include <libopencm3/stm32/f4/gpio.h>
+#elif defined(STM32L1)
+#include <libopencm3/stm32/l1/gpio.h>
+#else
+#error "invalid/unknown stm32 family for this code"
+#endif
void exti_set_trigger(u32 extis, exti_trigger_type trig)
{
@@ -121,18 +133,24 @@ void exti_select_source(u32 exti, u32 gpioport)
case GPIOE:
bits = 0xb;
break;
+#if defined(STM32L1)
+#else
case GPIOF:
bits = 0xa;
break;
case GPIOG:
bits = 0x9;
break;
+#endif
case GPIOH:
bits = 0x8;
break;
+#if defined(STM32L1)
+#else
case GPIOI:
bits = 0x7;
break;
+#endif
}
/* Ensure that only valid EXTI lines are used. */
diff --git a/lib/stm32/f1/Makefile b/lib/stm32/f1/Makefile
index ed8ae29..2572554 100644
--- a/lib/stm32/f1/Makefile
+++ b/lib/stm32/f1/Makefile
@@ -32,9 +32,10 @@ OBJS = rcc.o gpio.o usart.o adc.o spi.o flash.o \
rtc.o i2c.o dma.o exti.o ethernet.o \
usb_f103.o usb.o usb_control.o usb_standard.o can.o \
timer.o usb_f107.o desig.o crc.o dac.o iwdg.o pwr.o \
- usb_fx07_common.o
+ usb_fx07_common.o \
+ gpio_common_all.o
-VPATH += ../../usb:../:../../cm3
+VPATH += ../../usb:../:../../cm3:../common
include ../../Makefile.include
diff --git a/lib/stm32/f1/adc.c b/lib/stm32/f1/adc.c
index 0a05aac..71eb926 100644
--- a/lib/stm32/f1/adc.c
+++ b/lib/stm32/f1/adc.c
@@ -187,7 +187,7 @@ void adc_set_dual_mode(u32 mode)
This flag is set after all channels of a regular or injected group have been
converted.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
@returns bool. End of conversion flag.
*/
@@ -201,7 +201,7 @@ bool adc_eoc(u32 adc)
This flag is set after all channels of an injected group have been converted.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
@returns bool. End of conversion flag.
*/
@@ -217,7 +217,7 @@ The result read back is 12 bits, right or left aligned within the first 16 bits.
For ADC1 only, the higher 16 bits will hold the result from ADC2 if
an appropriate dual mode has been set @see adc_set_dual_mode.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
@returns Unsigned int32 conversion result.
*/
@@ -233,7 +233,7 @@ The result read back from the selected injected result register (one of four) is
12 bits, right or left aligned within the first 16 bits. The result can have a
negative value if the injected channel offset has been set @see adc_set_injected_offset.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
@param[in] reg Unsigned int8. Register number (1 ... 4).
@returns Unsigned int32 conversion result.
*/
@@ -260,7 +260,7 @@ This value is subtracted from the injected channel results after conversion
is complete, and can result in negative results. A separate value can be specified
for each injected data register.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
@param[in] reg Unsigned int8. Register number (1 ... 4).
@param[in] offset Unsigned int32.
*/
@@ -290,7 +290,7 @@ The analog watchdog allows the monitoring of an analog signal between two thresh
levels. The thresholds must be preset. Comparison is done before data alignment
takes place, so the thresholds are left-aligned.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_enable_analog_watchdog_regular(u32 adc)
@@ -301,7 +301,7 @@ void adc_enable_analog_watchdog_regular(u32 adc)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Disable Analog Watchdog for Regular Conversions
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_disable_analog_watchdog_regular(u32 adc)
@@ -316,7 +316,7 @@ The analog watchdog allows the monitoring of an analog signal between two thresh
levels. The thresholds must be preset. Comparison is done before data alignment
takes place, so the thresholds are left-aligned.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_enable_analog_watchdog_injected(u32 adc)
@@ -327,7 +327,7 @@ void adc_enable_analog_watchdog_injected(u32 adc)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Disable Analog Watchdog for Injected Conversions
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_disable_analog_watchdog_injected(u32 adc)
@@ -346,8 +346,8 @@ of the same length or until the whole group has all been converted. When the
the whole group has been converted, the next trigger will restart conversion
of the subgroup at the beginning of the whole group.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
-@param[in] length Unsigned int8. Number of channels in the group @ref adc_cr1_discnum
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
+@param[in] length Unsigned int8. Number of channels in the group @ref adc_cr1_discnum.
*/
void adc_enable_discontinuous_mode_regular(u32 adc, u8 length)
@@ -360,7 +360,7 @@ void adc_enable_discontinuous_mode_regular(u32 adc, u8 length)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Disable Discontinuous Mode for Regular Conversions
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_disable_discontinuous_mode_regular(u32 adc)
@@ -375,7 +375,7 @@ In this mode the ADC converts sequentially one channel of the defined group of
injected channels, cycling back to the first channel in the group once the
entire group has been converted.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_enable_discontinuous_mode_injected(u32 adc)
@@ -386,7 +386,7 @@ void adc_enable_discontinuous_mode_injected(u32 adc)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Disable Discontinuous Mode for Injected Conversions
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_disable_discontinuous_mode_injected(u32 adc)
@@ -413,7 +413,7 @@ void adc_enable_automatic_injected_group_conversion(u32 adc)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Disable Automatic Injected Conversions
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_disable_automatic_injected_group_conversion(u32 adc)
@@ -433,7 +433,7 @@ injected channels. If neither are enabled, the analog watchdog feature will be
disabled.
@ref adc_enable_analog_watchdog_injected, @ref adc_enable_analog_watchdog_regular.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_enable_analog_watchdog_on_all_channels(u32 adc)
@@ -453,8 +453,8 @@ injected channels. If neither are enabled, the analog watchdog feature will be
disabled. If both are enabled, the same channel number is monitored.
@ref adc_enable_analog_watchdog_injected, @ref adc_enable_analog_watchdog_regular.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
-@param[in] channel Unsigned int8. ADC channel number @ref adc_watchdog_channel
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
+@param[in] channel Unsigned int8. ADC channel number @ref adc_watchdog_channel.
*/
void adc_enable_analog_watchdog_on_selected_channel(u32 adc, u8 channel)
@@ -475,7 +475,7 @@ In this mode a conversion consists of a scan of the predefined set of channels,
regular and injected, each channel conversion immediately following the
previous one. It can use single, continuous or discontinuous mode.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_enable_scan_mode(u32 adc)
@@ -497,7 +497,7 @@ void adc_disable_scan_mode(u32 adc)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Enable Injected End-Of-Conversion Interrupt
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_enable_eoc_interrupt_injected(u32 adc)
@@ -508,7 +508,7 @@ void adc_enable_eoc_interrupt_injected(u32 adc)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Disable Injected End-Of-Conversion Interrupt
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_disable_eoc_interrupt_injected(u32 adc)
@@ -519,7 +519,7 @@ void adc_disable_eoc_interrupt_injected(u32 adc)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Enable Analog Watchdog Interrupt
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_enable_awd_interrupt(u32 adc)
@@ -530,7 +530,7 @@ void adc_enable_awd_interrupt(u32 adc)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Disable Analog Watchdog Interrupt
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_disable_awd_interrupt(u32 adc)
@@ -541,7 +541,7 @@ void adc_disable_awd_interrupt(u32 adc)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Enable Regular End-Of-Conversion Interrupt
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_enable_eoc_interrupt(u32 adc)
@@ -552,7 +552,7 @@ void adc_enable_eoc_interrupt(u32 adc)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Disable Regular End-Of-Conversion Interrupt
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_disable_eoc_interrupt(u32 adc)
@@ -566,7 +566,7 @@ void adc_disable_eoc_interrupt(u32 adc)
This enables both the sensor and the reference voltage measurements on channels
16 and 17.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_enable_temperature_sensor(u32 adc)
@@ -580,7 +580,7 @@ void adc_enable_temperature_sensor(u32 adc)
Disabling this will reduce power consumption from the sensor and the reference
voltage measurements.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_disable_temperature_sensor(u32 adc)
@@ -599,7 +599,7 @@ Note this is a software trigger and requires triggering to be enabled and the
trigger source to be set appropriately otherwise conversion will not start.
This is not the same as the ADC start conversion operation.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_start_conversion_regular(u32 adc)
@@ -622,7 +622,7 @@ Note this is a software trigger and requires triggering to be enabled and the
trigger source to be set appropriately otherwise conversion will not start.
This is not the same as the ADC start conversion operation.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_start_conversion_injected(u32 adc)
@@ -659,9 +659,9 @@ For ADC3
@li Timer 5 CC3 event
@li Software Start
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
@param[in] trigger Unsigned int8. Trigger identifier @ref adc_trigger_regular_12
-for ADC1 and ADC2, or @ref adc_trigger_regular_3 for ADC3
+for ADC1 and ADC2, or @ref adc_trigger_regular_3 for ADC3.
*/
void adc_enable_external_trigger_regular(u32 adc, u32 trigger)
@@ -677,7 +677,7 @@ void adc_enable_external_trigger_regular(u32 adc, u32 trigger)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Disable an External Trigger for Regular Channels
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_disable_external_trigger_regular(u32 adc)
@@ -710,9 +710,9 @@ For ADC3
@li Timer 5 CC4 event
@li Software Start
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
@param[in] trigger Unsigned int8. Trigger identifier @ref adc_trigger_injected_12
-for ADC1 and ADC2, or @ref adc_trigger_injected_3 for ADC3
+for ADC1 and ADC2, or @ref adc_trigger_injected_3 for ADC3.
*/
void adc_enable_external_trigger_injected(u32 adc, u32 trigger)
{
@@ -727,7 +727,7 @@ void adc_enable_external_trigger_injected(u32 adc, u32 trigger)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Disable an External Trigger for Injected Channels
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_disable_external_trigger_injected(u32 adc)
@@ -738,7 +738,7 @@ void adc_disable_external_trigger_injected(u32 adc)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Set the Data as Left Aligned
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_set_left_aligned(u32 adc)
@@ -749,7 +749,7 @@ void adc_set_left_aligned(u32 adc)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Set the Data as Right Aligned
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_set_right_aligned(u32 adc)
@@ -764,7 +764,7 @@ Only available for ADC1 through DMA1 channel1, and ADC3 through DMA2 channel5.
ADC2 will use DMA if it is set as slave in dual mode with ADC1 in DMA transfer
mode.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_enable_dma(u32 adc)
@@ -776,7 +776,7 @@ void adc_enable_dma(u32 adc)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Disable DMA Transfers
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_disable_dma(u32 adc)
@@ -791,7 +791,7 @@ void adc_disable_dma(u32 adc)
This resets the calibration registers. It is not clear if this is required to be
done before every calibration operation.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_reset_calibration(u32 adc)
@@ -810,7 +810,7 @@ until this happens and the ADC is ready for use.
The ADC must have been powered down for at least 2 ADC clock cycles, then powered on.
before calibration starts
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_calibration(u32 adc)
@@ -825,7 +825,7 @@ void adc_calibration(u32 adc)
In this mode the ADC starts a new conversion of a single channel or a channel
group immediately following completion of the previous channel group conversion.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_set_continuous_conversion_mode(u32 adc)
@@ -839,7 +839,7 @@ void adc_set_continuous_conversion_mode(u32 adc)
In this mode the ADC performs a conversion of one channel or a channel group
and stops.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_set_single_conversion_mode(u32 adc)
@@ -856,7 +856,7 @@ If the ADC is already on this function call will initiate a conversion.
@deprecated to be removed in a later release
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_on(u32 adc)
@@ -869,7 +869,7 @@ void adc_on(u32 adc)
Turn off the ADC to reduce power consumption to a few microamps.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
*/
void adc_off(u32 adc)
@@ -882,9 +882,9 @@ void adc_off(u32 adc)
The sampling time can be selected in ADC clock cycles from 1.5 to 239.5.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
-@param[in] channel Unsigned int8. ADC Channel integer 0..18 or from @ref adc_channel
-@param[in] time Unsigned int8. Sampling time selection from @ref adc_sample_rg
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
+@param[in] channel Unsigned int8. ADC Channel integer 0..18 or from @ref adc_channel.
+@param[in] time Unsigned int8. Sampling time selection from @ref adc_sample_rg.
*/
void adc_set_sample_time(u32 adc, u8 channel, u8 time)
@@ -910,8 +910,8 @@ void adc_set_sample_time(u32 adc, u8 channel, u8 time)
The sampling time can be selected in ADC clock cycles from 1.5 to 239.5, same for
all channels.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
-@param[in] time Unsigned int8. Sampling time selection from @ref adc_sample_rg
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
+@param[in] time Unsigned int8. Sampling time selection from @ref adc_sample_rg.
*/
void adc_set_sample_time_on_all_channels(u32 adc, u8 time)
@@ -931,8 +931,8 @@ void adc_set_sample_time_on_all_channels(u32 adc, u8 time)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Set Analog Watchdog Upper Threshold
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
-@param[in] threshold Unsigned int8. Upper threshold value
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
+@param[in] threshold Unsigned int8. Upper threshold value.
*/
void adc_set_watchdog_high_threshold(u32 adc, u16 threshold)
@@ -947,8 +947,8 @@ void adc_set_watchdog_high_threshold(u32 adc, u16 threshold)
/*-----------------------------------------------------------------------------*/
/** @brief ADC Set Analog Watchdog Lower Threshold
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
-@param[in] threshold Unsigned int8. Lower threshold value
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
+@param[in] threshold Unsigned int8. Lower threshold value.
*/
void adc_set_watchdog_low_threshold(u32 adc, u16 threshold)
@@ -967,7 +967,7 @@ Define a sequence of channels to be converted as a regular group with a length
from 1 to 16 channels. If this is called during conversion, the current conversion
is reset and conversion begins again with the newly defined group.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
@param[in] length Unsigned int8. Number of channels in the group.
@param[in] channel Unsigned int8[]. Set of channels in sequence, integers 0..18.
*/
@@ -1003,9 +1003,9 @@ Defines a sequence of channels to be converted as an injected group with a lengt
from 1 to 4 channels. If this is called during conversion, the current conversion
is reset and conversion begins again with the newly defined group.
-@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base
+@param[in] adc Unsigned int32. ADC block register address base @ref adc_reg_base.
@param[in] length Unsigned int8. Number of channels in the group.
-@param[in] channel Unsigned int8[]. Set of channels in sequence, integers 0..18
+@param[in] channel Unsigned int8[]. Set of channels in sequence, integers 0..18.
*/
void adc_set_injected_sequence(u32 adc, u8 length, u8 channel[])
diff --git a/lib/stm32/f1/dma.c b/lib/stm32/f1/dma.c
index c26020a..1f06c11 100644
--- a/lib/stm32/f1/dma.c
+++ b/lib/stm32/f1/dma.c
@@ -80,7 +80,7 @@ The interrupt flag for the channel is cleared. More than one interrupt for the
same channel may be cleared by using the logical OR of the interrupt flags.
@param[in] dma unsigned int32. DMA controller base address: DMA1 or DMA2
-@param[in] channel unsigned int8. Channel number: @ref dma_st_number
+@param[in] channel unsigned int8. Channel number: @ref dma_ch
@param[in] interrupts unsigned int32. Logical OR of interrupt numbers: @ref dma_if_offset
*/
@@ -97,8 +97,8 @@ void dma_clear_interrupt_flags(u32 dma, u8 channel, u32 interrupts)
The interrupt flag for the channel is returned.
@param[in] dma unsigned int32. DMA controller base address: DMA1 or DMA2
-@param[in] channel unsigned int8. Channel number: @ref dma_st_number
-@param[in] interrupt unsigned int32. Interrupt number: @ref dma_st_number
+@param[in] channel unsigned int8. Channel number: @ref dma_ch
+@param[in] interrupt unsigned int32. Interrupt number: @ref dma_ch
@returns bool interrupt flag is set.
*/
@@ -433,5 +433,10 @@ void dma_set_number_of_data(u32 dma, u8 channel, u16 number)
{
DMA_CNDTR(dma, channel) = number;
}
+
+void dma_clear_flag(u32 dma, u32 flag)
+{
+ DMA_ISR(dma) &= ~flag;
+}
/**@}*/
diff --git a/lib/stm32/f1/gpio.c b/lib/stm32/f1/gpio.c
index 0602012..2b33cad 100644
--- a/lib/stm32/f1/gpio.c
+++ b/lib/stm32/f1/gpio.c
@@ -1,4 +1,4 @@
-/** @defgroup STM32F1xx_gpio_file GPIO
+/** @defgroup gpio_file GPIO
@ingroup STM32F1xx
@@ -11,9 +11,6 @@
@date 18 August 2012
-This library supports the General Purpose I/O System in the STM32F1xx series
-of ARM Cortex Microcontrollers by ST Microelectronics.
-
Each I/O port has 16 individually configurable bits. Many I/O pins share GPIO
functionality with a number of alternate functions and must be configured to the
alternate function mode if these are to be accessed. A feature is available to
@@ -55,7 +52,7 @@ Example 1: Digital input on port C12
@endcode
LGPL License Terms @ref lgpl_license
- */
+*/
/*
* This file is part of the libopencm3 project.
*
@@ -75,25 +72,10 @@ LGPL License Terms @ref lgpl_license
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
-/*
- * Basic GPIO handling API.
- *
- * Examples:
- * gpio_set_mode(GPIOC, GPIO_MODE_OUTPUT_2_MHZ,
- * GPIO_CNF_OUTPUT_PUSHPULL, GPIO12);
- * gpio_set(GPIOB, GPIO4);
- * gpio_clear(GPIOG, GPIO2 | GPIO9);
- * gpio_get(GPIOC, GPIO1);
- * gpio_toggle(GPIOA, GPIO7 | GPIO8);
- * reg16 = gpio_port_read(GPIOD);
- * gpio_port_write(GPIOF, 0xc8fe);
- *
- * TODO:
- * - GPIO remapping support
- */
-/**@{*/
+#include <libopencm3/stm32/gpio.h>
+#include <libopencm3/stm32/common/gpio_common_all.h>
-#include <libopencm3/stm32/f1/gpio.h>
+/**@{*/
/*-----------------------------------------------------------------------------*/
/** @brief Set GPIO Pin Mode
@@ -146,116 +128,6 @@ void gpio_set_mode(u32 gpioport, u8 mode, u8 cnf, u16 gpios)
}
/*-----------------------------------------------------------------------------*/
-/** @brief Set a Group of Pins Atomic
-
-Set one or more pins of the given GPIO port to 1 in an atomic operation.
-
-@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
-@param[in] gpios Unsigned int16. Pin identifiers @ref gpio_pin_id
- If multiple pins are to be changed, use logical OR '|' to separate them.
-*/
-void gpio_set(u32 gpioport, u16 gpios)
-{
- GPIO_BSRR(gpioport) = gpios;
-}
-
-/*-----------------------------------------------------------------------------*/
-/** @brief Clear a Group of Pins Atomic
-
-Clear one or more pins of the given GPIO port to 0 in an atomic operation.
-
-@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
-@param[in] gpios Unsigned int16. Pin identifiers @ref gpio_pin_id
- If multiple pins are to be changed, use logical OR '|' to separate them.
-*/
-void gpio_clear(u32 gpioport, u16 gpios)
-{
- GPIO_BRR(gpioport) = gpios;
-}
-
-/*-----------------------------------------------------------------------------*/
-/** @brief Read a Group of Pins.
-
-@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
-@param[in] gpios Unsigned int16. Pin identifiers @ref gpio_pin_id
- If multiple pins are to be read, use logical OR '|' to separate them.
-@return Unsigned int16 value of the pin values. The bit position of the pin value
- returned corresponds to the pin number.
-*/
-u16 gpio_get(u32 gpioport, u16 gpios)
-{
- return gpio_port_read(gpioport) & gpios;
-}
-
-/*-----------------------------------------------------------------------------*/
-/** @brief Toggle a Group of Pins
-
-Toggle one or more pins of the given GPIO port. This is not an atomic operation.
-
-@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
-@param[in] gpios Unsigned int16. Pin identifiers @ref gpio_pin_id
- If multiple pins are to be changed, use logical OR '|' to separate them.
-*/
-void gpio_toggle(u32 gpioport, u16 gpios)
-{
- GPIO_ODR(gpioport) ^= gpios;
-}
-
-/*-----------------------------------------------------------------------------*/
-/** @brief Read from a Port
-
-Read the current value of the given GPIO port. Only the lower 16 bits contain
-valid pin data.
-
-@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
-@return Unsigned int16. The value held in the specified GPIO port.
-*/
-u16 gpio_port_read(u32 gpioport)
-{
- return (u16)GPIO_IDR(gpioport);
-}
-
-/*-----------------------------------------------------------------------------*/
-/** @brief Write to a Port
-
-Write a value to the given GPIO port.
-
-@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
-@param[in] data Unsigned int16. The value to be written to the GPIO port.
-*/
-void gpio_port_write(u32 gpioport, u16 data)
-{
- GPIO_ODR(gpioport) = data;
-}
-
-/*-----------------------------------------------------------------------------*/
-/** @brief Lock the Configuration of a Group of Pins
-
-The configuration of one or more pins of the given GPIO port is locked. There is
-no mechanism to unlock these via software. Unlocking occurs at the next reset.
-
-@param[in] gpioport Unsigned int32. Port identifier @ref gpio_port_id
-@param[in] gpios Unsigned int16. Pin identifiers @ref gpio_pin_id
- If multiple pins are to be locked, use logical OR '|' to separate them.
-*/
-void gpio_port_config_lock(u32 gpioport, u16 gpios)
-{
- u32 reg32;
-
- /* Special "Lock Key Writing Sequence", see datasheet. */
- GPIO_LCKR(gpioport) = GPIO_LCKK | gpios; /* Set LCKK. */
- GPIO_LCKR(gpioport) = ~GPIO_LCKK & gpios; /* Clear LCKK. */
- GPIO_LCKR(gpioport) = GPIO_LCKK | gpios; /* Set LCKK. */
- reg32 = GPIO_LCKR(gpioport); /* Read LCKK. */
- reg32 = GPIO_LCKR(gpioport); /* Read LCKK again. */
-
- /* Tell the compiler the variable is actually used. It will get optimized out anyways. */
- reg32 = reg32;
-
- /* If (reg32 & GPIO_LCKK) is true, the lock is now active. */
-}
-
-/*-----------------------------------------------------------------------------*/
/** @brief Map the EVENTOUT signal
Enable the EVENTOUT signal and select the port and pin to be used.
@@ -292,7 +164,7 @@ value cannot be ascertained from the hardware.
*/
void gpio_primary_remap(u8 swjdisable, u32 maps)
{
- AFIO_MAPR = swjdisable | (maps & 0x1FFFFF);
+ AFIO_MAPR |= swjdisable | (maps & 0x1FFFFF);
}
/*-----------------------------------------------------------------------------*/
@@ -310,7 +182,7 @@ The AFIO remapping feature is used only with the STM32F10x series.
*/
void gpio_secondary_remap(u32 maps)
{
- AFIO_MAPR2 = maps;
+ AFIO_MAPR2 |= maps;
}
/**@}*/
diff --git a/lib/stm32/f1/rcc.c b/lib/stm32/f1/rcc.c
index ab3350b..9cd8658 100644
--- a/lib/stm32/f1/rcc.c
+++ b/lib/stm32/f1/rcc.c
@@ -71,6 +71,12 @@ void rcc_osc_ready_int_clear(osc_t osc)
case PLL:
RCC_CIR |= RCC_CIR_PLLRDYC;
break;
+ case PLL2:
+ RCC_CIR |= RCC_CIR_PLL2RDYC;
+ break;
+ case PLL3:
+ RCC_CIR |= RCC_CIR_PLL3RDYC;
+ break;
case HSE:
RCC_CIR |= RCC_CIR_HSERDYC;
break;
@@ -98,6 +104,12 @@ void rcc_osc_ready_int_enable(osc_t osc)
case PLL:
RCC_CIR |= RCC_CIR_PLLRDYIE;
break;
+ case PLL2:
+ RCC_CIR |= RCC_CIR_PLL2RDYIE;
+ break;
+ case PLL3:
+ RCC_CIR |= RCC_CIR_PLL3RDYIE;
+ break;
case HSE:
RCC_CIR |= RCC_CIR_HSERDYIE;
break;
@@ -125,6 +137,12 @@ void rcc_osc_ready_int_disable(osc_t osc)
case PLL:
RCC_CIR &= ~RCC_CIR_PLLRDYIE;
break;
+ case PLL2:
+ RCC_CIR &= ~RCC_CIR_PLL2RDYIE;
+ break;
+ case PLL3:
+ RCC_CIR &= ~RCC_CIR_PLL3RDYIE;
+ break;
case HSE:
RCC_CIR &= ~RCC_CIR_HSERDYIE;
break;
@@ -153,6 +171,12 @@ int rcc_osc_ready_int_flag(osc_t osc)
case PLL:
return ((RCC_CIR & RCC_CIR_PLLRDYF) != 0);
break;
+ case PLL2:
+ return ((RCC_CIR & RCC_CIR_PLL2RDYF) != 0);
+ break;
+ case PLL3:
+ return ((RCC_CIR & RCC_CIR_PLL3RDYF) != 0);
+ break;
case HSE:
return ((RCC_CIR & RCC_CIR_HSERDYF) != 0);
break;
@@ -203,6 +227,12 @@ void rcc_wait_for_osc_ready(osc_t osc)
case PLL:
while ((RCC_CR & RCC_CR_PLLRDY) == 0);
break;
+ case PLL2:
+ while ((RCC_CR & RCC_CR_PLL2RDY) == 0);
+ break;
+ case PLL3:
+ while ((RCC_CR & RCC_CR_PLL3RDY) == 0);
+ break;
case HSE:
while ((RCC_CR & RCC_CR_HSERDY) == 0);
break;
@@ -238,6 +268,12 @@ void rcc_osc_on(osc_t osc)
case PLL:
RCC_CR |= RCC_CR_PLLON;
break;
+ case PLL2:
+ RCC_CR |= RCC_CR_PLL2ON;
+ break;
+ case PLL3:
+ RCC_CR |= RCC_CR_PLL3ON;
+ break;
case HSE:
RCC_CR |= RCC_CR_HSEON;
break;
@@ -273,6 +309,12 @@ void rcc_osc_off(osc_t osc)
case PLL:
RCC_CR &= ~RCC_CR_PLLON;
break;
+ case PLL2:
+ RCC_CR &= ~RCC_CR_PLL2ON;
+ break;
+ case PLL3:
+ RCC_CR &= ~RCC_CR_PLL3ON;
+ break;
case HSE:
RCC_CR &= ~RCC_CR_HSEON;
break;
@@ -331,6 +373,8 @@ void rcc_osc_bypass_enable(osc_t osc)
RCC_BDCR |= RCC_BDCR_LSEBYP;
break;
case PLL:
+ case PLL2:
+ case PLL3:
case HSI:
case LSI:
/* Do nothing, only HSE/LSE allowed here. */
@@ -361,6 +405,8 @@ void rcc_osc_bypass_disable(osc_t osc)
RCC_BDCR &= ~RCC_BDCR_LSEBYP;
break;
case PLL:
+ case PLL2:
+ case PLL3:
case HSI:
case LSI:
/* Do nothing, only HSE/LSE allowed here. */
@@ -485,6 +531,40 @@ void rcc_set_pll_multiplication_factor(u32 mul)
}
/*-----------------------------------------------------------------------------*/
+/** @brief RCC Set the PLL2 Multiplication Factor.
+
+@note This only has effect when the PLL is disabled.
+
+@param[in] mul Unsigned int32. PLL multiplication factor @ref rcc_cfgr_pmf
+*/
+
+void rcc_set_pll2_multiplication_factor(u32 mul)
+{
+ u32 reg32;
+
+ reg32 = RCC_CFGR2;
+ reg32 &= ~((1 << 11) | (1 << 10) | (1 << 9) | (1 << 8));
+ RCC_CFGR2 = (reg32 | (mul << 8));
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief RCC Set the PLL3 Multiplication Factor.
+
+@note This only has effect when the PLL is disabled.
+
+@param[in] mul Unsigned int32. PLL multiplication factor @ref rcc_cfgr_pmf
+*/
+
+void rcc_set_pll3_multiplication_factor(u32 mul)
+{
+ u32 reg32;
+
+ reg32 = RCC_CFGR2;
+ reg32 &= ~((1 << 15) | (1 << 14) | (1 << 13) | (1 << 12));
+ RCC_CFGR2 = (reg32 | (mul << 12));
+}
+
+/*-----------------------------------------------------------------------------*/
/** @brief RCC Set the PLL Clock Source.
@note This only has effect when the PLL is disabled.
@@ -602,6 +682,36 @@ void rcc_set_usbpre(u32 usbpre)
RCC_CFGR = (reg32 | (usbpre << 22));
}
+void rcc_set_prediv1(u32 prediv)
+{
+ u32 reg32;
+ reg32 = RCC_CFGR2;
+ reg32 &= ~(1 << 3) | (1 << 2) | (1 << 1) | (1 << 0);
+ RCC_CFGR2 |= (reg32 | prediv);
+}
+
+void rcc_set_prediv2(u32 prediv)
+{
+ u32 reg32;
+ reg32 = RCC_CFGR2;
+ reg32 &= ~(1 << 7) | (1 << 6) | (1 << 5) | (1 << 4);
+ RCC_CFGR2 |= (reg32 | (prediv << 4));
+}
+
+void rcc_set_prediv1_source(u32 rccsrc)
+{
+ RCC_CFGR2 &= ~(1 << 16);
+ RCC_CFGR2 |= (rccsrc << 16);
+}
+
+void rcc_set_mco(u32 mcosrc)
+{
+ u32 reg32;
+ reg32 = RCC_CFGR;
+ reg32 &= ~((1 << 27) | (1 << 26) | (1 << 25) | (1 << 24));
+ RCC_CFGR |= (reg32 | (mcosrc << 24));
+}
+
/*-----------------------------------------------------------------------------*/
/** @brief RCC Get the System Clock Source.
@@ -1031,6 +1141,63 @@ void rcc_clock_setup_in_hse_16mhz_out_72mhz(void)
}
/*-----------------------------------------------------------------------------*/
+/** @brief RCC Set System Clock PLL at 72MHz from HSE at 25MHz
+
+*/
+
+void rcc_clock_setup_in_hse_25mhz_out_72mhz(void)
+{
+ /* Enable external high-speed oscillator 25MHz. */
+ rcc_osc_on(HSE);
+ rcc_wait_for_osc_ready(HSE);
+ rcc_set_sysclk_source(RCC_CFGR_SW_SYSCLKSEL_HSECLK);
+
+ /*
+ * Sysclk runs with 72MHz -> 2 waitstates.
+ * 0WS from 0-24MHz
+ * 1WS from 24-48MHz
+ * 2WS from 48-72MHz
+ */
+ flash_set_ws(FLASH_LATENCY_2WS);
+
+ /*
+ * Set prescalers for AHB, ADC, ABP1, ABP2.
+ * Do this before touching the PLL (TODO: why?).
+ */
+ rcc_set_hpre(RCC_CFGR_HPRE_SYSCLK_NODIV); /* Set. 72MHz Max. 72MHz */
+ rcc_set_adcpre(RCC_CFGR_ADCPRE_PCLK2_DIV6); /* Set. 12MHz Max. 14MHz */
+ rcc_set_ppre1(RCC_CFGR_PPRE1_HCLK_DIV2); /* Set. 36MHz Max. 36MHz */
+ rcc_set_ppre2(RCC_CFGR_PPRE2_HCLK_NODIV); /* Set. 72MHz Max. 72MHz */
+
+ /* Set pll2 prediv and multiplier */
+ rcc_set_prediv2(RCC_CFGR2_PREDIV2_DIV5);
+ rcc_set_pll2_multiplication_factor(RCC_CFGR2_PLL2MUL_PLL2_CLK_MUL8);
+
+ /* Enable PLL2 oscillator and wait for it to stabilize */
+ rcc_osc_on(PLL2);
+ rcc_wait_for_osc_ready(PLL2);
+
+ /* Set pll1 prediv/multiplier, prediv1 src, and usb predivider */
+ rcc_set_pllxtpre(RCC_CFGR_PLLXTPRE_HSE_CLK);
+ rcc_set_prediv1_source(RCC_CFGR2_PREDIV1SRC_PLL2_CLK);
+ rcc_set_prediv1(RCC_CFGR2_PREDIV_DIV5);
+ rcc_set_pll_multiplication_factor(RCC_CFGR_PLLMUL_PLL_CLK_MUL9);
+ rcc_set_pll_source(RCC_CFGR_PLLSRC_PREDIV1_CLK);
+ rcc_set_usbpre(RCC_CFGR_USBPRE_PLL_VCO_CLK_DIV3);
+
+ /* enable PLL1 and wait for it to stabilize */
+ rcc_osc_on(PLL);
+ rcc_wait_for_osc_ready(PLL);
+
+ /* Select PLL as SYSCLK source. */
+ rcc_set_sysclk_source(RCC_CFGR_SW_SYSCLKSEL_PLLCLK);
+
+ /* Set the peripheral clock frequencies used */
+ rcc_ppre1_frequency = 36000000;
+ rcc_ppre2_frequency = 72000000;
+}
+
+/*-----------------------------------------------------------------------------*/
/** @brief RCC Reset the backup domain
The backup domain register is reset to disable all controls.
diff --git a/lib/stm32/f1/rtc.c b/lib/stm32/f1/rtc.c
index 08a4953..cfc5f5b 100644
--- a/lib/stm32/f1/rtc.c
+++ b/lib/stm32/f1/rtc.c
@@ -67,6 +67,8 @@ void rtc_awake_from_off(osc_t clock_source)
RCC_BDCR |= (1 << 9) | (1 << 8);
break;
case PLL:
+ case PLL2:
+ case PLL3:
case HSI:
/* Unusable clock source, here to prevent warnings. */
/* Turn off clock sources to RTC. */
diff --git a/lib/stm32/f2/Makefile b/lib/stm32/f2/Makefile
index 5cbb977..b890fa4 100644
--- a/lib/stm32/f2/Makefile
+++ b/lib/stm32/f2/Makefile
@@ -29,8 +29,9 @@ CFLAGS = -Os -g -Wall -Wextra -I../../../include -fno-common \
# ARFLAGS = rcsv
ARFLAGS = rcs
OBJS = rcc.o gpio.o usart.o spi.o flash.o \
- i2c.o exti.o timer.o
+ i2c.o exti2.o timer.o \
+ gpio_common_all.o gpio_common_f24.o
-VPATH += ../../usb:../:../../cm3
+VPATH += ../../usb:../:../../cm3:../common
include ../../Makefile.include
diff --git a/lib/stm32/f2/exti.c b/lib/stm32/f2/exti.c
deleted file mode 100644
index 5280914..0000000
--- a/lib/stm32/f2/exti.c
+++ /dev/null
@@ -1,146 +0,0 @@
-/*
- * This file is part of the libopencm3 project.
- *
- * Copyright (C) 2010 Mark Butler <mbutler@physics.otago.ac.nz>
- *
- * 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 3 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, see <http://www.gnu.org/licenses/>.
- */
-
-#include <libopencm3/stm32/exti.h>
-#include <libopencm3/stm32/f2/syscfg.h>
-#include <libopencm3/stm32/f2/gpio.h>
-
-void exti_set_trigger(u32 extis, exti_trigger_type trig)
-{
- switch (trig) {
- case EXTI_TRIGGER_RISING:
- EXTI_RTSR |= extis;
- EXTI_FTSR &= ~extis;
- break;
- case EXTI_TRIGGER_FALLING:
- EXTI_RTSR &= ~extis;
- EXTI_FTSR |= extis;
- break;
- case EXTI_TRIGGER_BOTH:
- EXTI_RTSR |= extis;
- EXTI_FTSR |= extis;
- break;
- }
-}
-
-void exti_enable_request(u32 extis)
-{
- /* Enable interrupts. */
- EXTI_IMR |= extis;
-
- /* Enable events. */
- EXTI_EMR |= extis;
-}
-
-void exti_disable_request(u32 extis)
-{
- /* Disable interrupts. */
- EXTI_IMR &= ~extis;
-
- /* Disable events. */
- EXTI_EMR &= ~extis;
-}
-
-/*
- * Reset the interrupt request by writing a 1 to the corresponding
- * pending bit register.
- */
-void exti_reset_request(u32 extis)
-{
- EXTI_PR = extis;
-}
-
-/*
- * Remap an external interrupt line to the corresponding pin on the
- * specified GPIO port.
- *
- * TODO: This could be rewritten in fewer lines of code.
- */
-void exti_select_source(u32 exti, u32 gpioport)
-{
- u8 shift, bits;
-
- shift = bits = 0;
-
- switch (exti) {
- case EXTI0:
- case EXTI4:
- case EXTI8:
- case EXTI12:
- shift = 0;
- break;
- case EXTI1:
- case EXTI5:
- case EXTI9:
- case EXTI13:
- shift = 4;
- break;
- case EXTI2:
- case EXTI6:
- case EXTI10:
- case EXTI14:
- shift = 8;
- break;
- case EXTI3:
- case EXTI7:
- case EXTI11:
- case EXTI15:
- shift = 12;
- break;
- }
-
- switch (gpioport) {
- case GPIOA:
- bits = 0xf;
- break;
- case GPIOB:
- bits = 0xe;
- break;
- case GPIOC:
- bits = 0xd;
- break;
- case GPIOD:
- bits = 0xc;
- break;
- case GPIOE:
- bits = 0xb;
- break;
- case GPIOF:
- bits = 0xa;
- break;
- case GPIOG:
- bits = 0x9;
- break;
- }
-
- /* Ensure that only valid EXTI lines are used. */
- if (exti < EXTI4) {
- SYSCFG_EXTICR1 &= ~(0x000F << shift);
- SYSCFG_EXTICR1 |= (~bits << shift);
- } else if (exti < EXTI8) {
- SYSCFG_EXTICR2 &= ~(0x000F << shift);
- SYSCFG_EXTICR2 |= (~bits << shift);
- } else if (exti < EXTI12) {
- SYSCFG_EXTICR3 &= ~(0x000F << shift);
- SYSCFG_EXTICR3 |= (~bits << shift);
- } else if (exti < EXTI16) {
- SYSCFG_EXTICR4 &= ~(0x000F << shift);
- SYSCFG_EXTICR4 |= (~bits << shift);
- }
-}
diff --git a/lib/stm32/f2/gpio.c b/lib/stm32/f2/gpio.c
index c577c3a..a2dfc88 100644
--- a/lib/stm32/f2/gpio.c
+++ b/lib/stm32/f2/gpio.c
@@ -1,8 +1,14 @@
+/** @defgroup gpio_file GPIO
+
+@ingroup STM32F2xx
+
+@brief <b>libopencm3 STM32F2xx General Purpose I/O</b>
+
+*/
+
/*
* This file is part of the libopencm3 project.
*
- * Copyright (C) 2011 Fergus Noble <fergusnoble@gmail.com>
- *
* 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 3 of the License, or
@@ -17,126 +23,6 @@
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
-#include <libopencm3/stm32/f2/gpio.h>
-
-void gpio_mode_setup(u32 gpioport, u8 mode, u8 pull_up_down, u16 gpios)
-{
- u16 i;
- u32 moder, pupd;
-
- /*
- * We want to set the config only for the pins mentioned in gpios,
- * but keeping the others, so read out the actual config first.
- */
- moder = GPIO_MODER(gpioport);
- pupd = GPIO_PUPDR(gpioport);
-
- for (i = 0; i < 16; i++) {
- if (!((1 << i) & gpios))
- continue;
-
- moder &= ~GPIO_MODE_MASK(i);
- moder |= GPIO_MODE(i, mode);
- pupd &= ~GPIO_PUPD_MASK(i);
- pupd |= GPIO_PUPD(i, pull_up_down);
- }
-
- /* Set mode and pull up/down control registers. */
- GPIO_MODER(gpioport) = moder;
- GPIO_PUPDR(gpioport) = pupd;
-}
-
-void gpio_set_output_options(u32 gpioport, u8 otype, u8 speed, u16 gpios)
-{
- u16 i;
- u32 ospeedr;
-
- if (otype == 0x1)
- GPIO_OTYPER(gpioport) |= gpios;
- else
- GPIO_OTYPER(gpioport) &= ~gpios;
-
- ospeedr = GPIO_OSPEEDR(gpioport);
-
- for (i = 0; i < 16; i++) {
- if (!((1 << i) & gpios))
- continue;
- ospeedr &= ~GPIO_OSPEED_MASK(i);
- ospeedr |= GPIO_OSPEED(i, speed);
- }
-
- GPIO_OSPEEDR(gpioport) = ospeedr;
-}
-
-void gpio_set_af(u32 gpioport, u8 alt_func_num, u16 gpios)
-{
- u16 i;
- u32 afrl, afrh;
-
- afrl = GPIO_AFRL(gpioport);
- afrh = GPIO_AFRH(gpioport);
-
- for (i = 0; i < 8; i++) {
- if (!((1 << i) & gpios))
- continue;
- afrl &= ~GPIO_AFR_MASK(i);
- afrl |= GPIO_AFR(i, alt_func_num);
- }
-
- for (i = 8; i < 16; i++) {
- if (!((1 << i) & gpios))
- continue;
- afrh &= ~GPIO_AFR_MASK(i - 8);
- afrh |= GPIO_AFR(i - 8, alt_func_num);
- }
-
- GPIO_AFRL(gpioport) = afrl;
- GPIO_AFRH(gpioport) = afrh;
-}
-
-void gpio_set(u32 gpioport, u16 gpios)
-{
- GPIO_BSRR(gpioport) = gpios;
-}
-
-void gpio_clear(u32 gpioport, u16 gpios)
-{
- GPIO_BSRR(gpioport) = gpios << 16;
-}
-
-u16 gpio_get(u32 gpioport, u16 gpios)
-{
- return gpio_port_read(gpioport) & gpios;
-}
-
-void gpio_toggle(u32 gpioport, u16 gpios)
-{
- GPIO_ODR(gpioport) ^= gpios;
-}
-
-u16 gpio_port_read(u32 gpioport)
-{
- return (u16)GPIO_IDR(gpioport);
-}
-
-void gpio_port_write(u32 gpioport, u16 data)
-{
- GPIO_ODR(gpioport) = data;
-}
-
-void gpio_port_config_lock(u32 gpioport, u16 gpios)
-{
- u32 reg32;
-
- /* Special "Lock Key Writing Sequence", see datasheet. */
- GPIO_LCKR(gpioport) = GPIO_LCKK | gpios; /* Set LCKK. */
- GPIO_LCKR(gpioport) = ~GPIO_LCKK & gpios; /* Clear LCKK. */
- GPIO_LCKR(gpioport) = GPIO_LCKK | gpios; /* Set LCKK. */
- reg32 = GPIO_LCKR(gpioport); /* Read LCKK. */
- reg32 = GPIO_LCKR(gpioport); /* Read LCKK again. */
-
- /* Tell the compiler the variable is actually used. It will get optimized out anyways. */
- reg32 = reg32;
+#include <libopencm3/stm32/gpio.h>
+#include <libopencm3/stm32/common/gpio_common_f24.h>
- /* If (reg32 & GPIO_LCKK) is true, the lock is now active. */
-}
diff --git a/lib/stm32/f4/Makefile b/lib/stm32/f4/Makefile
index 614a37e..c9ad847 100644
--- a/lib/stm32/f4/Makefile
+++ b/lib/stm32/f4/Makefile
@@ -30,10 +30,11 @@ CFLAGS = -Os -g -Wall -Wextra -I../../../include -fno-common \
# ARFLAGS = rcsv
ARFLAGS = rcs
OBJS = rcc.o gpio.o usart.o spi.o flash.o \
- i2c.o exti.o pwr.o timer.o \
+ i2c.o exti2.o pwr.o timer.o \
usb.o usb_standard.o usb_control.o usb_fx07_common.o usb_f107.o \
- usb_f207.o adc.o dma.o
+ usb_f207.o adc.o dma.o \
+ gpio_common_all.o gpio_common_f24.o
-VPATH += ../../usb:../:../../cm3
+VPATH += ../../usb:../:../../cm3:../common
include ../../Makefile.include
diff --git a/lib/stm32/f4/gpio.c b/lib/stm32/f4/gpio.c
index aa2fda4..96a6f45 100644
--- a/lib/stm32/f4/gpio.c
+++ b/lib/stm32/f4/gpio.c
@@ -1,8 +1,14 @@
+/** @defgroup gpio_file GPIO
+
+@ingroup STM32F4xx
+
+@brief <b>libopencm3 STM32F4xx General Purpose I/O</b>
+
+*/
+
/*
* This file is part of the libopencm3 project.
*
- * Copyright (C) 2011 Fergus Noble <fergusnoble@gmail.com>
- *
* 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 3 of the License, or
@@ -17,126 +23,6 @@
* along with this library. If not, see <http://www.gnu.org/licenses/>.
*/
-#include <libopencm3/stm32/f4/gpio.h>
-
-void gpio_mode_setup(u32 gpioport, u8 mode, u8 pull_up_down, u16 gpios)
-{
- u16 i;
- u32 moder, pupd;
-
- /*
- * We want to set the config only for the pins mentioned in gpios,
- * but keeping the others, so read out the actual config first.
- */
- moder = GPIO_MODER(gpioport);
- pupd = GPIO_PUPDR(gpioport);
-
- for (i = 0; i < 16; i++) {
- if (!((1 << i) & gpios))
- continue;
-
- moder &= ~GPIO_MODE_MASK(i);
- moder |= GPIO_MODE(i, mode);
- pupd &= ~GPIO_PUPD_MASK(i);
- pupd |= GPIO_PUPD(i, pull_up_down);
- }
-
- /* Set mode and pull up/down control registers. */
- GPIO_MODER(gpioport) = moder;
- GPIO_PUPDR(gpioport) = pupd;
-}
-
-void gpio_set_output_options(u32 gpioport, u8 otype, u8 speed, u16 gpios)
-{
- u16 i;
- u32 ospeedr;
-
- if (otype == 0x1)
- GPIO_OTYPER(gpioport) |= gpios;
- else
- GPIO_OTYPER(gpioport) &= ~gpios;
-
- ospeedr = GPIO_OSPEEDR(gpioport);
-
- for (i = 0; i < 16; i++) {
- if (!((1 << i) & gpios))
- continue;
- ospeedr &= ~GPIO_OSPEED_MASK(i);
- ospeedr |= GPIO_OSPEED(i, speed);
- }
-
- GPIO_OSPEEDR(gpioport) = ospeedr;
-}
-
-void gpio_set_af(u32 gpioport, u8 alt_func_num, u16 gpios)
-{
- u16 i;
- u32 afrl, afrh;
-
- afrl = GPIO_AFRL(gpioport);
- afrh = GPIO_AFRH(gpioport);
-
- for (i = 0; i < 8; i++) {
- if (!((1 << i) & gpios))
- continue;
- afrl &= ~GPIO_AFR_MASK(i);
- afrl |= GPIO_AFR(i, alt_func_num);
- }
-
- for (i = 8; i < 16; i++) {
- if (!((1 << i) & gpios))
- continue;
- afrh &= ~GPIO_AFR_MASK(i - 8);
- afrh |= GPIO_AFR(i - 8, alt_func_num);
- }
-
- GPIO_AFRL(gpioport) = afrl;
- GPIO_AFRH(gpioport) = afrh;
-}
-
-void gpio_set(u32 gpioport, u16 gpios)
-{
- GPIO_BSRR(gpioport) = gpios;
-}
-
-void gpio_clear(u32 gpioport, u16 gpios)
-{
- GPIO_BSRR(gpioport) = gpios << 16;
-}
-
-u16 gpio_get(u32 gpioport, u16 gpios)
-{
- return gpio_port_read(gpioport) & gpios;
-}
-
-void gpio_toggle(u32 gpioport, u16 gpios)
-{
- GPIO_ODR(gpioport) ^= gpios;
-}
-
-u16 gpio_port_read(u32 gpioport)
-{
- return (u16)GPIO_IDR(gpioport);
-}
-
-void gpio_port_write(u32 gpioport, u16 data)
-{
- GPIO_ODR(gpioport) = data;
-}
-
-void gpio_port_config_lock(u32 gpioport, u16 gpios)
-{
- u32 reg32;
-
- /* Special "Lock Key Writing Sequence", see datasheet. */
- GPIO_LCKR(gpioport) = GPIO_LCKK | gpios; /* Set LCKK. */
- GPIO_LCKR(gpioport) = ~GPIO_LCKK & gpios; /* Clear LCKK. */
- GPIO_LCKR(gpioport) = GPIO_LCKK | gpios; /* Set LCKK. */
- reg32 = GPIO_LCKR(gpioport); /* Read LCKK. */
- reg32 = GPIO_LCKR(gpioport); /* Read LCKK again. */
-
- /* Tell the compiler the variable is actually used. It will get optimized out anyways. */
- reg32 = reg32;
+#include <libopencm3/stm32/gpio.h>
+#include <libopencm3/stm32/common/gpio_common_f24.h>
- /* If (reg32 & GPIO_LCKK) is true, the lock is now active. */
-}
diff --git a/lib/stm32/i2c.c b/lib/stm32/i2c.c
index e1d3a09..a67bece 100644
--- a/lib/stm32/i2c.c
+++ b/lib/stm32/i2c.c
@@ -125,6 +125,18 @@ void i2c_send_stop(u32 i2c)
}
/*-----------------------------------------------------------------------------*/
+/** @brief I2C Clear Stop Flag.
+
+Clear the "Send Stop" flag in the I2C config register
+
+@param[in] i2c Unsigned int32. I2C register base address @ref i2c_reg_base.
+*/
+void i2c_clear_stop(u32 i2c)
+{
+ I2C_CR1(i2c) &= ~I2C_CR1_STOP;
+}
+
+/*-----------------------------------------------------------------------------*/
/** @brief I2C Set the 7 bit Slave Address for the Peripheral.
This sets an address for Slave mode operation, in 7 bit form.
@@ -269,5 +281,135 @@ void i2c_send_data(u32 i2c, u8 data)
I2C_DR(i2c) = data;
}
-/**@}*/
+/*-----------------------------------------------------------------------------*/
+/** @brief I2C Get Data.
+
+@param[in] i2c Unsigned int32. I2C register base address @ref i2c_reg_base.
+*/
+uint8_t i2c_get_data(u32 i2c)
+{
+ return I2C_DR(i2c) & 0xff;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief I2C Enable Interrupt
+
+@param[in] i2c Unsigned int32. I2C register base address @ref i2c_reg_base.
+@param[in] interrupt Unsigned int32. Interrupt to enable.
+*/
+void i2c_enable_interrupt(u32 i2c, u32 interrupt)
+{
+ I2C_CR2(i2c) |= interrupt;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief I2C Disable Interrupt
+
+@param[in] i2c Unsigned int32. I2C register base address @ref i2c_reg_base.
+@param[in] interrupt Unsigned int32. Interrupt to disable.
+*/
+void i2c_disable_interrupt(u32 i2c, u32 interrupt)
+{
+ I2C_CR2(i2c) &= ~interrupt;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief I2C Enable ACK
+
+Enables acking of own 7/10 bit address
+@param[in] i2c Unsigned int32. I2C register base address @ref i2c_reg_base.
+*/
+void i2c_enable_ack(u32 i2c)
+{
+ I2C_CR1(i2c) |= I2C_CR1_ACK;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief I2C Disable ACK
+
+Disables acking of own 7/10 bit address
+@param[in] i2c Unsigned int32. I2C register base address @ref i2c_reg_base.
+*/
+void i2c_disable_ack(u32 i2c)
+{
+ I2C_CR1(i2c) &= ~I2C_CR1_ACK;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief I2C NACK Next Byte
+
+Causes the I2C controller to NACK the reception of the next byte
+@param[in] i2c Unsigned int32. I2C register base address @ref i2c_reg_base.
+*/
+void i2c_nack_next(u32 i2c)
+{
+ I2C_CR1(i2c) |= I2C_CR1_POS;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief I2C NACK Next Byte
+
+Causes the I2C controller to NACK the reception of the current byte
+
+@param[in] i2c Unsigned int32. I2C register base address @ref i2c_reg_base.
+*/
+void i2c_nack_current(u32 i2c)
+{
+ I2C_CR1(i2c) &= ~I2C_CR1_POS;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief I2C Set clock duty cycle
+
+@param[in] i2c Unsigned int32. I2C register base address @ref i2c_reg_base.
+@param[in] dutycycle Unsigned int32. I2C duty cycle @ref i2c_duty_cycle.
+*/
+void i2c_set_dutycycle(u32 i2c, u32 dutycycle)
+{
+ if (dutycycle == I2C_CCR_DUTY_DIV2)
+ I2C_CCR(i2c) &= ~I2C_CCR_DUTY;
+ else
+ I2C_CCR(i2c) |= I2C_CCR_DUTY;
+}
+/*-----------------------------------------------------------------------------*/
+/** @brief I2C Enable DMA
+
+@param[in] i2c Unsigned int32. I2C register base address @ref i2c_reg_base.
+*/
+void i2c_enable_dma(u32 i2c)
+{
+ I2C_CR2(i2c) |= I2C_CR2_DMAEN;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief I2C Disable DMA
+
+@param[in] i2c Unsigned int32. I2C register base address @ref i2c_reg_base.
+*/
+void i2c_disable_dma(u32 i2c)
+{
+ I2C_CR2(i2c) &= ~I2C_CR2_DMAEN;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief I2C Set DMA last transfer
+
+@param[in] i2c Unsigned int32. I2C register base address @ref i2c_reg_base.
+*/
+void i2c_set_dma_last_transfer(u32 i2c)
+{
+ I2C_CR2(i2c) |= I2C_CR2_LAST;
+}
+
+/*-----------------------------------------------------------------------------*/
+/** @brief I2C Clear DMA last transfer
+
+@param[in] i2c Unsigned int32. I2C register base address @ref i2c_reg_base.
+*/
+void i2c_clear_dma_last_transfer(u32 i2c)
+{
+ I2C_CR2(i2c) &= ~I2C_CR2_LAST;
+}
+
+/**@}*/
diff --git a/lib/stm32/l1/Makefile b/lib/stm32/l1/Makefile
new file mode 100644
index 0000000..7f3e157
--- /dev/null
+++ b/lib/stm32/l1/Makefile
@@ -0,0 +1,37 @@
+##
+## This file is part of the libopencm3 project.
+##
+## Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+##
+## 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 3 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, see <http://www.gnu.org/licenses/>.
+##
+
+LIBNAME = libopencm3_stm32l1
+
+PREFIX ?= arm-none-eabi
+#PREFIX ?= arm-elf
+CC = $(PREFIX)-gcc
+AR = $(PREFIX)-ar
+CFLAGS = -Os -g -Wall -Wextra -I../../../include -fno-common \
+ -mcpu=cortex-m3 -mthumb -Wstrict-prototypes \
+ -ffunction-sections -fdata-sections -MD -DSTM32L1
+# ARFLAGS = rcsv
+ARFLAGS = rcs
+OBJS = rcc.o gpio.o desig.o crc.o usart.o exti2.o \
+ gpio_common_all.o gpio_common_f24.o
+
+VPATH += ../../usb:../:../../cm3:../common
+
+include ../../Makefile.include
+
diff --git a/lib/stm32/l1/gpio.c b/lib/stm32/l1/gpio.c
new file mode 100644
index 0000000..7fc2012
--- /dev/null
+++ b/lib/stm32/l1/gpio.c
@@ -0,0 +1,28 @@
+/** @defgroup gpio_file GPIO
+
+@ingroup STM32L1xx
+
+@brief <b>libopencm3 STM32L1xx General Purpose I/O</b>
+
+*/
+
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * 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 3 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, see <http://www.gnu.org/licenses/>.
+ */
+
+#include <libopencm3/stm32/gpio.h>
+#include <libopencm3/stm32/common/gpio_common_all.h>
+
diff --git a/lib/stm32/l1/libopencm3_stm32l1.ld b/lib/stm32/l1/libopencm3_stm32l1.ld
new file mode 100644
index 0000000..9d165f6
--- /dev/null
+++ b/lib/stm32/l1/libopencm3_stm32l1.ld
@@ -0,0 +1,83 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+ *
+ * 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 3 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, see <http://www.gnu.org/licenses/>.
+ */
+
+/* Generic linker script for STM32 targets using libopencm3. */
+
+/* Memory regions must be defined in the ld script which includes this one. */
+
+/* Enforce emmition of the vector table. */
+EXTERN (vector_table)
+
+/* Define the entry point of the output file. */
+ENTRY(reset_handler)
+
+/* Define sections. */
+SECTIONS
+{
+ .text : {
+ *(.vectors) /* Vector table */
+ *(.text*) /* Program code */
+ . = ALIGN(4);
+ *(.rodata*) /* Read-only data */
+ . = ALIGN(4);
+ } >rom
+
+ /*
+ * Another section used by C++ stuff, appears when using newlib with
+ * 64bit (long long) printf support
+ */
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } >rom
+ .ARM.exidx : {
+ __exidx_start = .;
+ *(.ARM.exidx*)
+ __exidx_end = .;
+ } >rom
+
+ . = ALIGN(4);
+ _etext = .;
+
+ .data : {
+ _data = .;
+ *(.data*) /* Read-write initialized data */
+ . = ALIGN(4);
+ _edata = .;
+ } >ram AT >rom
+ _data_loadaddr = LOADADDR(.data);
+
+ .bss : {
+ *(.bss*) /* Read-write zero initialized data */
+ *(COMMON)
+ . = ALIGN(4);
+ _ebss = .;
+ } >ram
+
+ /*
+ * The .eh_frame section appears to be used for C++ exception handling.
+ * You may need to fix this if you're using C++.
+ */
+ /DISCARD/ : { *(.eh_frame) }
+
+ . = ALIGN(4);
+ end = .;
+}
+
+PROVIDE(_stack = ORIGIN(ram) + LENGTH(ram));
+
diff --git a/lib/stm32/l1/rcc.c b/lib/stm32/l1/rcc.c
new file mode 100644
index 0000000..a023622
--- /dev/null
+++ b/lib/stm32/l1/rcc.c
@@ -0,0 +1,357 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2009 Federico Ruiz-Ugalde <memeruiz at gmail dot com>
+ * Copyright (C) 2009 Uwe Hermann <uwe@hermann-uwe.de>
+ * Copyright (C) 2010 Thomas Otto <tommi@viadmin.org>
+ * Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au>
+ *
+ * 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 3 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, see <http://www.gnu.org/licenses/>.
+ * Based on the F4 code...
+ */
+
+#include <libopencm3/stm32/l1/rcc.h>
+
+/* Set the default ppre1 and ppre2 peripheral clock frequencies after reset. */
+u32 rcc_ppre1_frequency = 2097000;
+u32 rcc_ppre2_frequency = 2097000;
+
+void rcc_osc_ready_int_clear(osc_t osc)
+{
+ switch (osc) {
+ case PLL:
+ RCC_CIR |= RCC_CIR_PLLRDYC;
+ break;
+ case HSE:
+ RCC_CIR |= RCC_CIR_HSERDYC;
+ break;
+ case HSI:
+ RCC_CIR |= RCC_CIR_HSIRDYC;
+ break;
+ case LSE:
+ RCC_CIR |= RCC_CIR_LSERDYC;
+ break;
+ case LSI:
+ RCC_CIR |= RCC_CIR_LSIRDYC;
+ break;
+ case MSI:
+ RCC_CIR |= RCC_CIR_MSIRDYC;
+ break;
+ }
+}
+
+void rcc_osc_ready_int_enable(osc_t osc)
+{
+ switch (osc) {
+ case PLL:
+ RCC_CIR |= RCC_CIR_PLLRDYIE;
+ break;
+ case HSE:
+ RCC_CIR |= RCC_CIR_HSERDYIE;
+ break;
+ case HSI:
+ RCC_CIR |= RCC_CIR_HSIRDYIE;
+ break;
+ case LSE:
+ RCC_CIR |= RCC_CIR_LSERDYIE;
+ break;
+ case LSI:
+ RCC_CIR |= RCC_CIR_LSIRDYIE;
+ break;
+ case MSI:
+ RCC_CIR |= RCC_CIR_MSIRDYIE;
+ break;
+ }
+}
+
+void rcc_osc_ready_int_disable(osc_t osc)
+{
+ switch (osc) {
+ case PLL:
+ RCC_CIR &= ~RCC_CIR_PLLRDYIE;
+ break;
+ case HSE:
+ RCC_CIR &= ~RCC_CIR_HSERDYIE;
+ break;
+ case HSI:
+ RCC_CIR &= ~RCC_CIR_HSIRDYIE;
+ break;
+ case LSE:
+ RCC_CIR &= ~RCC_CIR_LSERDYIE;
+ break;
+ case LSI:
+ RCC_CIR &= ~RCC_CIR_LSIRDYIE;
+ break;
+ case MSI:
+ RCC_CIR &= ~RCC_CIR_MSIRDYIE;
+ break;
+ }
+}
+
+int rcc_osc_ready_int_flag(osc_t osc)
+{
+ switch (osc) {
+ case PLL:
+ return ((RCC_CIR & RCC_CIR_PLLRDYF) != 0);
+ break;
+ case HSE:
+ return ((RCC_CIR & RCC_CIR_HSERDYF) != 0);
+ break;
+ case HSI:
+ return ((RCC_CIR & RCC_CIR_HSIRDYF) != 0);
+ break;
+ case LSE:
+ return ((RCC_CIR & RCC_CIR_LSERDYF) != 0);
+ break;
+ case LSI:
+ return ((RCC_CIR & RCC_CIR_LSIRDYF) != 0);
+ break;
+ case MSI:
+ return ((RCC_CIR & RCC_CIR_MSIRDYF) != 0);
+ break;
+ }
+
+ /* Shouldn't be reached. */
+ return -1;
+}
+
+void rcc_css_int_clear(void)
+{
+ RCC_CIR |= RCC_CIR_CSSC;
+}
+
+int rcc_css_int_flag(void)
+{
+ return ((RCC_CIR & RCC_CIR_CSSF) != 0);
+}
+
+void rcc_wait_for_osc_ready(osc_t osc)
+{
+ switch (osc) {
+ case PLL:
+ while ((RCC_CR & RCC_CR_PLLRDY) == 0);
+ break;
+ case HSE:
+ while ((RCC_CR & RCC_CR_HSERDY) == 0);
+ break;
+ case HSI:
+ while ((RCC_CR & RCC_CR_HSIRDY) == 0);
+ break;
+ case MSI:
+ while ((RCC_CR & RCC_CR_MSIRDY) == 0);
+ break;
+ case LSE:
+ while ((RCC_CSR & RCC_CSR_LSERDY) == 0);
+ break;
+ case LSI:
+ while ((RCC_CSR & RCC_CSR_LSIRDY) == 0);
+ break;
+ }
+}
+
+void rcc_wait_for_sysclk_status(osc_t osc)
+{
+ switch (osc) {
+ case PLL:
+ while ((RCC_CFGR & ((1 << 1) | (1 << 0))) != RCC_CFGR_SWS_SYSCLKSEL_PLLCLK);
+ break;
+ case HSE:
+ while ((RCC_CFGR & ((1 << 1) | (1 << 0))) != RCC_CFGR_SWS_SYSCLKSEL_HSECLK);
+ break;
+ case HSI:
+ while ((RCC_CFGR & ((1 << 1) | (1 << 0))) != RCC_CFGR_SWS_SYSCLKSEL_HSICLK);
+ break;
+ case MSI:
+ while ((RCC_CFGR & ((1 << 1) | (1 << 0))) != RCC_CFGR_SWS_SYSCLKSEL_MSICLK);
+ break;
+ default:
+ /* Shouldn't be reached. */
+ break;
+ }
+}
+
+void rcc_osc_on(osc_t osc)
+{
+ switch (osc) {
+ case PLL:
+ RCC_CR |= RCC_CR_PLLON;
+ break;
+ case MSI:
+ RCC_CR |= RCC_CR_MSION;
+ break;
+ case HSE:
+ RCC_CR |= RCC_CR_HSEON;
+ break;
+ case HSI:
+ RCC_CR |= RCC_CR_HSION;
+ break;
+ case LSE:
+ RCC_CSR |= RCC_CSR_LSEON;
+ break;
+ case LSI:
+ RCC_CSR |= RCC_CSR_LSION;
+ break;
+ }
+}
+
+void rcc_osc_off(osc_t osc)
+{
+ switch (osc) {
+ case PLL:
+ RCC_CR &= ~RCC_CR_PLLON;
+ break;
+ case MSI:
+ RCC_CR &= ~RCC_CR_MSION;
+ break;
+ case HSE:
+ RCC_CR &= ~RCC_CR_HSEON;
+ break;
+ case HSI:
+ RCC_CR &= ~RCC_CR_HSION;
+ break;
+ case LSE:
+ RCC_CSR &= ~RCC_CSR_LSEON;
+ break;
+ case LSI:
+ RCC_CSR &= ~RCC_CSR_LSION;
+ break;
+ }
+}
+
+void rcc_css_enable(void)
+{
+ RCC_CR |= RCC_CR_CSSON;
+}
+
+void rcc_css_disable(void)
+{
+ RCC_CR &= ~RCC_CR_CSSON;
+}
+
+void rcc_osc_bypass_enable(osc_t osc)
+{
+ switch (osc) {
+ case HSE:
+ RCC_CR |= RCC_CR_HSEBYP;
+ break;
+ case LSE:
+ RCC_CSR |= RCC_CSR_LSEBYP;
+ break;
+ case PLL:
+ case HSI:
+ case LSI:
+ case MSI:
+ /* Do nothing, only HSE/LSE allowed here. */
+ break;
+ }
+}
+
+void rcc_osc_bypass_disable(osc_t osc)
+{
+ switch (osc) {
+ case HSE:
+ RCC_CR &= ~RCC_CR_HSEBYP;
+ break;
+ case LSE:
+ RCC_CSR &= ~RCC_CSR_LSEBYP;
+ break;
+ case PLL:
+ case HSI:
+ case LSI:
+ case MSI:
+ /* Do nothing, only HSE/LSE allowed here. */
+ break;
+ }
+}
+
+void rcc_peripheral_enable_clock(volatile u32 *reg, u32 en)
+{
+ *reg |= en;
+}
+
+void rcc_peripheral_disable_clock(volatile u32 *reg, u32 en)
+{
+ *reg &= ~en;
+}
+
+void rcc_peripheral_reset(volatile u32 *reg, u32 reset)
+{
+ *reg |= reset;
+}
+
+void rcc_peripheral_clear_reset(volatile u32 *reg, u32 clear_reset)
+{
+ *reg &= ~clear_reset;
+}
+
+void rcc_set_sysclk_source(u32 clk)
+{
+ u32 reg32;
+
+ reg32 = RCC_CFGR;
+ reg32 &= ~((1 << 1) | (1 << 0));
+ RCC_CFGR = (reg32 | clk);
+}
+
+void rcc_set_pll_source(u32 pllsrc)
+{
+ u32 reg32;
+
+ reg32 = RCC_CFGR;
+ reg32 &= ~(1 << 16);
+ RCC_CFGR = (reg32 | (pllsrc << 16));
+}
+
+void rcc_set_ppre2(u32 ppre2)
+{
+ u32 reg32;
+
+ reg32 = RCC_CFGR;
+ reg32 &= ~((1 << 13) | (1 << 12) | (1 << 11));
+ RCC_CFGR = (reg32 | (ppre2 << 11));
+}
+
+void rcc_set_ppre1(u32 ppre1)
+{
+ u32 reg32;
+
+ reg32 = RCC_CFGR;
+ reg32 &= ~((1 << 10) | (1 << 9) | (1 << 8));
+ RCC_CFGR = (reg32 | (ppre1 << 8));
+}
+
+void rcc_set_hpre(u32 hpre)
+{
+ u32 reg32;
+
+ reg32 = RCC_CFGR;
+ reg32 &= ~((1 << 4) | (1 << 5) | (1 << 6) | (1 << 7));
+ RCC_CFGR = (reg32 | (hpre << 4));
+}
+
+void rcc_set_rtcpre(u32 rtcpre)
+{
+ u32 reg32;
+
+ reg32 = RCC_CR;
+ reg32 &= ~((1 << 30) | (1 << 29));
+ RCC_CR = (reg32 | (rtcpre << 29));
+}
+
+u32 rcc_system_clock_source(void)
+{
+ /* Return the clock source which is used as system clock. */
+ return ((RCC_CFGR & 0x000c) >> 2);
+}
+
diff --git a/lib/stm32/l1/stm32l15xx8.ld b/lib/stm32/l1/stm32l15xx8.ld
new file mode 100644
index 0000000..1f20f57
--- /dev/null
+++ b/lib/stm32/l1/stm32l15xx8.ld
@@ -0,0 +1,31 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au
+ *
+ * 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 3 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, see <http://www.gnu.org/licenses/>.
+ */
+
+/* Linker script for STM32L15xx8, 64K flash, 10K RAM. */
+
+/* Define memory regions. */
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x08000000, LENGTH = 64K
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 10K
+}
+
+/* Include the common ld script. */
+INCLUDE libopencm3_stm32l1.ld
+
diff --git a/lib/stm32/l1/stm32l15xxb.ld b/lib/stm32/l1/stm32l15xxb.ld
new file mode 100644
index 0000000..4c14b71
--- /dev/null
+++ b/lib/stm32/l1/stm32l15xxb.ld
@@ -0,0 +1,31 @@
+/*
+ * This file is part of the libopencm3 project.
+ *
+ * Copyright (C) 2012 Karl Palsson <karlp@tweak.net.au
+ *
+ * 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 3 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, see <http://www.gnu.org/licenses/>.
+ */
+
+/* Linker script for STM32L15xxB, 128K flash, 16K RAM. */
+
+/* Define memory regions. */
+MEMORY
+{
+ rom (rx) : ORIGIN = 0x08000000, LENGTH = 128K
+ ram (rwx) : ORIGIN = 0x20000000, LENGTH = 16K
+}
+
+/* Include the common ld script. */
+INCLUDE libopencm3_stm32l1.ld
+
diff --git a/lib/stm32/usart.c b/lib/stm32/usart.c
index 454df41..cb46db8 100644
--- a/lib/stm32/usart.c
+++ b/lib/stm32/usart.c
@@ -46,6 +46,8 @@ LGPL License Terms @ref lgpl_license
# include <libopencm3/stm32/f2/rcc.h>
#elif defined(STM32F4)
# include <libopencm3/stm32/f4/rcc.h>
+#elif defined(STM32L1)
+# include <libopencm3/stm32/l1/rcc.h>
#else
# error "stm32 family not defined."
#endif
diff --git a/lib/usb/usb.c b/lib/usb/usb.c
index ecebde2..0799202 100644
--- a/lib/usb/usb.c
+++ b/lib/usb/usb.c
@@ -44,7 +44,7 @@ u8 usbd_control_buffer[128] __attribute__((weak));
usbd_device *usbd_init(const usbd_driver *driver,
const struct usb_device_descriptor *dev,
const struct usb_config_descriptor *conf,
- const char **strings)
+ const char **strings, int num_strings)
{
usbd_device *usbd_dev;
@@ -54,6 +54,7 @@ usbd_device *usbd_init(const usbd_driver *driver,
usbd_dev->desc = dev;
usbd_dev->config = conf;
usbd_dev->strings = strings;
+ usbd_dev->num_strings = num_strings;
usbd_dev->ctrl_buf = usbd_control_buffer;
usbd_dev->ctrl_buf_len = sizeof(usbd_control_buffer);
diff --git a/lib/usb/usb_control.c b/lib/usb/usb_control.c
index 245ab1c..82843df 100644
--- a/lib/usb/usb_control.c
+++ b/lib/usb/usb_control.c
@@ -99,11 +99,12 @@ static int usb_control_request_dispatch(usbd_device *usbd_dev,
&(usbd_dev->control_state.ctrl_buf),
&(usbd_dev->control_state.ctrl_len),
&(usbd_dev->control_state.complete));
- if (result)
+ if (result == USBD_REQ_HANDLED ||
+ result == USBD_REQ_NOTSUPP)
return result;
}
}
-
+
/* Try standard request if not already handled. */
return _usbd_standard_request(usbd_dev, req,
&(usbd_dev->control_state.ctrl_buf),
diff --git a/lib/usb/usb_private.h b/lib/usb/usb_private.h
index 2506ba5..454e8c6 100644
--- a/lib/usb/usb_private.h
+++ b/lib/usb/usb_private.h
@@ -29,6 +29,7 @@ struct _usbd_device {
const struct usb_device_descriptor *desc;
const struct usb_config_descriptor *config;
const char **strings;
+ int num_strings;
u8 *ctrl_buf; /**< Internal buffer used for control transfers */
u16 ctrl_buf_len;
diff --git a/lib/usb/usb_standard.c b/lib/usb/usb_standard.c
index 5a92cd8..e14fee3 100644
--- a/lib/usb/usb_standard.c
+++ b/lib/usb/usb_standard.c
@@ -90,52 +90,75 @@ static u16 build_config_descriptor(usbd_device *usbd_dev,
return total;
}
+static int usb_descriptor_type(u16 wValue)
+{
+ return wValue >> 8;
+}
+
+static int usb_descriptor_index(u16 wValue)
+{
+ return wValue & 0xFF;
+}
+
static int usb_standard_get_descriptor(usbd_device *usbd_dev,
struct usb_setup_data *req,
u8 **buf, u16 *len)
{
- int i;
+ int i, array_idx, descr_idx;
struct usb_string_descriptor *sd;
- switch (req->wValue >> 8) {
+ descr_idx = usb_descriptor_index(req->wValue);
+
+ switch (usb_descriptor_type(req->wValue)) {
case USB_DT_DEVICE:
*buf = (u8 *) usbd_dev->desc;
*len = MIN(*len, usbd_dev->desc->bLength);
- return 1;
+ return USBD_REQ_HANDLED;
case USB_DT_CONFIGURATION:
*buf = usbd_dev->ctrl_buf;
- *len = build_config_descriptor(usbd_dev, req->wValue & 0xff,
- *buf, *len);
- return 1;
+ *len = build_config_descriptor(usbd_dev, descr_idx, *buf, *len);
+ return USBD_REQ_HANDLED;
case USB_DT_STRING:
sd = (struct usb_string_descriptor *)usbd_dev->ctrl_buf;
- if (!usbd_dev->strings)
- return 0; /* Device doesn't support strings. */
+ if (descr_idx == 0) {
+ /* Send sane Language ID descriptor... */
+ sd->wData[0] = USB_LANGID_ENGLISH_US;
+ sd->bLength = sizeof(sd->bLength) + sizeof(sd->bDescriptorType)
+ + sizeof(sd->wData[0]);
- /* Check that string index is in range. */
- for (i = 0; i <= (req->wValue & 0xff); i++)
- if (usbd_dev->strings[i] == NULL)
- return 0;
+ *len = MIN(*len, sd->bLength);
+ } else {
+ array_idx = descr_idx - 1;
- sd->bLength = strlen(usbd_dev->strings[req->wValue & 0xff])
- * 2 + 2;
- sd->bDescriptorType = USB_DT_STRING;
+ if (!usbd_dev->strings)
+ return USBD_REQ_NOTSUPP; /* Device doesn't support strings. */
+ /* Check that string index is in range. */
+ if (array_idx >= usbd_dev->num_strings)
+ return USBD_REQ_NOTSUPP;
- *buf = (u8 *)sd;
- *len = MIN(*len, sd->bLength);
+ /* Strings with Language ID differnet from
+ * USB_LANGID_ENGLISH_US are not supported */
+ if (req->wIndex != USB_LANGID_ENGLISH_US)
+ return USBD_REQ_NOTSUPP;
- for (i = 0; i < (*len / 2) - 1; i++)
- sd->wData[i] =
- usbd_dev->strings[req->wValue & 0xff][i];
+ /* Ths string is returned as UTF16, hence the multiplication */
+ sd->bLength = strlen(usbd_dev->strings[array_idx]) * 2 +
+ sizeof(sd->bLength) + sizeof(sd->bDescriptorType);
- /* Send sane Language ID descriptor... */
- if ((req->wValue & 0xff) == 0)
- sd->wData[0] = 0x409;
+ *len = MIN(*len, sd->bLength);
- return 1;
+ for (i = 0; i < (*len / 2) - 1; i++)
+ sd->wData[i] =
+ usbd_dev->strings[array_idx][i];
+ }
+
+ sd->bDescriptorType = USB_DT_STRING;
+ *buf = (u8 *)sd;
+
+ return USBD_REQ_HANDLED;
}
- return 0;
+ return USBD_REQ_NOTSUPP;
}
static int usb_standard_set_address(usbd_device *usbd_dev,