summaryrefslogtreecommitdiff
path: root/nuttx/arch/arm
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/arch/arm')
-rw-r--r--nuttx/arch/arm/Kconfig1
-rw-r--r--nuttx/arch/arm/include/armv7-m/irq.h21
-rw-r--r--nuttx/arch/arm/src/arm/up_assert.c4
-rw-r--r--nuttx/arch/arm/src/armv7-m/svcall.h2
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_assert.c4
-rwxr-xr-xnuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S2
-rw-r--r--nuttx/arch/arm/src/armv7-m/up_svcall.c2
-rw-r--r--nuttx/arch/arm/src/common/up_internal.h5
-rw-r--r--nuttx/arch/arm/src/stm32/Kconfig69
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_i2c.c383
-rw-r--r--nuttx/arch/arm/src/stm32/stm32_spi.c31
11 files changed, 328 insertions, 196 deletions
diff --git a/nuttx/arch/arm/Kconfig b/nuttx/arch/arm/Kconfig
index 3bd531232..2a7ea10b5 100644
--- a/nuttx/arch/arm/Kconfig
+++ b/nuttx/arch/arm/Kconfig
@@ -103,6 +103,7 @@ config ARCH_CHIP_STM32
bool "STMicro STM32"
select ARCH_HAVE_CMNVECTOR
select ARCH_HAVE_MPU
+ select ARCH_HAVE_I2CRESET
---help---
STMicro STM32 architectures (ARM Cortex-M3/4).
diff --git a/nuttx/arch/arm/include/armv7-m/irq.h b/nuttx/arch/arm/include/armv7-m/irq.h
index 6cef85c02..606b3988f 100644
--- a/nuttx/arch/arm/include/armv7-m/irq.h
+++ b/nuttx/arch/arm/include/armv7-m/irq.h
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/include/armv7-m/irq.h
*
- * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011-2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -48,6 +48,7 @@
#include <nuttx/irq.h>
#ifndef __ASSEMBLY__
+# include <nuttx/compiler.h>
# include <stdint.h>
#endif
@@ -131,6 +132,7 @@ struct xcptcontext
/* Disable IRQs */
+static inline void irqdisable(void) inline_function;
static inline void irqdisable(void)
{
__asm__ __volatile__ ("\tcpsid i\n");
@@ -138,6 +140,7 @@ static inline void irqdisable(void)
/* Save the current primask state & disable IRQs */
+static inline irqstate_t irqsave(void) inline_function;
static inline irqstate_t irqsave(void)
{
unsigned short primask;
@@ -153,11 +156,13 @@ static inline irqstate_t irqsave(void)
: "=r" (primask)
:
: "memory");
+
return primask;
}
/* Enable IRQs */
+static inline void irqenable(void) inline_function;
static inline void irqenable(void)
{
__asm__ __volatile__ ("\tcpsie i\n");
@@ -165,6 +170,7 @@ static inline void irqenable(void)
/* Restore saved primask state */
+static inline void irqrestore(irqstate_t primask) inline_function;
static inline void irqrestore(irqstate_t primask)
{
/* If bit 0 of the primask is 0, then we need to restore
@@ -184,6 +190,7 @@ static inline void irqrestore(irqstate_t primask)
/* Get/set the primask register */
+static inline uint8_t getprimask(void) inline_function;
static inline uint8_t getprimask(void)
{
uint32_t primask;
@@ -193,9 +200,11 @@ static inline uint8_t getprimask(void)
: "=r" (primask)
:
: "memory");
+
return (uint8_t)primask;
}
+static inline void setprimask(uint32_t primask) inline_function;
static inline void setprimask(uint32_t primask)
{
__asm__ __volatile__
@@ -208,18 +217,22 @@ static inline void setprimask(uint32_t primask)
/* Get/set the basepri register */
+static inline uint8_t getbasepri(void) inline_function;
static inline uint8_t getbasepri(void)
{
uint32_t basepri;
+
__asm__ __volatile__
(
"\tmrs %0, basepri\n"
: "=r" (basepri)
:
: "memory");
+
return (uint8_t)basepri;
}
+static inline void setbasepri(uint32_t basepri) inline_function;
static inline void setbasepri(uint32_t basepri)
{
__asm__ __volatile__
@@ -232,6 +245,7 @@ static inline void setbasepri(uint32_t basepri)
/* Get/set IPSR */
+static inline uint32_t getipsr(void) inline_function;
static inline uint32_t getipsr(void)
{
uint32_t ipsr;
@@ -241,9 +255,11 @@ static inline uint32_t getipsr(void)
: "=r" (ipsr)
:
: "memory");
+
return ipsr;
}
+static inline void setipsr(uint32_t ipsr) inline_function;
static inline void setipsr(uint32_t ipsr)
{
__asm__ __volatile__
@@ -256,6 +272,7 @@ static inline void setipsr(uint32_t ipsr)
/* Get/set CONTROL */
+static inline uint32_t getcontrol(void) inline_function;
static inline uint32_t getcontrol(void)
{
uint32_t control;
@@ -265,9 +282,11 @@ static inline uint32_t getcontrol(void)
: "=r" (control)
:
: "memory");
+
return control;
}
+static inline void setcontrol(uint32_t control) inline_function;
static inline void setcontrol(uint32_t control)
{
__asm__ __volatile__
diff --git a/nuttx/arch/arm/src/arm/up_assert.c b/nuttx/arch/arm/src/arm/up_assert.c
index 023e6e22d..3d75a4655 100644
--- a/nuttx/arch/arm/src/arm/up_assert.c
+++ b/nuttx/arch/arm/src/arm/up_assert.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/arm/up_assert.c
*
- * Copyright (C) 2007-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007-2010, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -252,7 +252,7 @@ static void up_dumpstate(void)
* Name: _up_assert
****************************************************************************/
-static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
+static void _up_assert(int errorcode) /* noreturn_function */
{
/* Are we in an interrupt handler or the idle task? */
diff --git a/nuttx/arch/arm/src/armv7-m/svcall.h b/nuttx/arch/arm/src/armv7-m/svcall.h
index 9a4db89b1..675829799 100644
--- a/nuttx/arch/arm/src/armv7-m/svcall.h
+++ b/nuttx/arch/arm/src/armv7-m/svcall.h
@@ -74,7 +74,7 @@
/* SYS call 1:
*
- * void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
+ * void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
*/
#define SYS_restore_context (1)
diff --git a/nuttx/arch/arm/src/armv7-m/up_assert.c b/nuttx/arch/arm/src/armv7-m/up_assert.c
index 2662cbe37..282ff6a57 100644
--- a/nuttx/arch/arm/src/armv7-m/up_assert.c
+++ b/nuttx/arch/arm/src/armv7-m/up_assert.c
@@ -1,7 +1,7 @@
/****************************************************************************
* arch/arm/src/armv7-m/up_assert.c
*
- * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010, 2012 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -262,7 +262,7 @@ static void up_dumpstate(void)
* Name: _up_assert
****************************************************************************/
-static void _up_assert(int errorcode) /* __attribute__ ((noreturn)) */
+static void _up_assert(int errorcode) /* noreturn_function */
{
/* Are we in an interrupt handler or the idle task? */
diff --git a/nuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S b/nuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S
index 3ce51c9cd..4c77b66b8 100755
--- a/nuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S
+++ b/nuttx/arch/arm/src/armv7-m/up_fullcontextrestore.S
@@ -69,7 +69,7 @@
* Description:
* Restore the current thread context. Full prototype is:
*
- * void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
+ * void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
*
* Return:
* None
diff --git a/nuttx/arch/arm/src/armv7-m/up_svcall.c b/nuttx/arch/arm/src/armv7-m/up_svcall.c
index 5a4d64fe2..d32f0afc2 100644
--- a/nuttx/arch/arm/src/armv7-m/up_svcall.c
+++ b/nuttx/arch/arm/src/armv7-m/up_svcall.c
@@ -280,7 +280,7 @@ int up_svcall(int irq, FAR void *context)
/* R0=SYS_restore_context: This a restore context command:
*
- * void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
+ * void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
*
* At this point, the following values are saved in context:
*
diff --git a/nuttx/arch/arm/src/common/up_internal.h b/nuttx/arch/arm/src/common/up_internal.h
index 45cb1dcc0..9f20775c0 100644
--- a/nuttx/arch/arm/src/common/up_internal.h
+++ b/nuttx/arch/arm/src/common/up_internal.h
@@ -40,7 +40,10 @@
* Included Files
****************************************************************************/
+#include <nuttx/config.h>
+
#ifndef __ASSEMBLY__
+# include <nuttx/compiler.h>
# include <sys/types.h>
# include <stdint.h>
#endif
@@ -223,7 +226,7 @@ extern void up_boot(void);
extern void up_copystate(uint32_t *dest, uint32_t *src);
extern void up_decodeirq(uint32_t *regs);
extern int up_saveusercontext(uint32_t *saveregs);
-extern void up_fullcontextrestore(uint32_t *restoreregs) __attribute__ ((noreturn));
+extern void up_fullcontextrestore(uint32_t *restoreregs) noreturn_function;
extern void up_switchcontext(uint32_t *saveregs, uint32_t *restoreregs);
/* Signal handling **********************************************************/
diff --git a/nuttx/arch/arm/src/stm32/Kconfig b/nuttx/arch/arm/src/stm32/Kconfig
index b5d0306da..8b0cea32e 100644
--- a/nuttx/arch/arm/src/stm32/Kconfig
+++ b/nuttx/arch/arm/src/stm32/Kconfig
@@ -191,14 +191,17 @@ menu "STM32 Peripheral Support"
config STM32_ADC1
bool "ADC1"
default n
+ select STM32_ADC
config STM32_ADC2
bool "ADC2"
default n
+ select STM32_ADC
config STM32_ADC3
bool "ADC3"
default n
+ select STM32_ADC
config STM32_CRC
bool "CRC"
@@ -228,12 +231,14 @@ config STM32_CAN1
bool "CAN1"
default n
select CAN
+ select STM32_CAN
config STM32_CAN2
bool "CAN2"
default n
depends on STM32_STM32F20XX || STM32_STM32F40XX
select CAN
+ select STM32_CAN
config STM32_CCMDATARAM
bool "CMD/DATA RAM"
@@ -248,10 +253,12 @@ config STM32_CRYP
config STM32_DAC1
bool "DAC1"
default n
+ select STM32_DAC
config STM32_DAC2
bool "DAC2"
default n
+ select STM32_DAC
config STM32_DCMI
bool "DCMI"
@@ -276,15 +283,18 @@ config STM32_HASH
config STM32_I2C1
bool "I2C1"
default n
+ select STM32_I2C
config STM32_I2C2
bool "I2C2"
default n
+ select STM32_I2C
config STM32_I2C3
bool "I2C3"
default n
depends on STM32_STM32F20XX || STM32_STM32F40XX
+ select STM32_I2C
config STM32_IWDG
bool "IWDG"
@@ -319,23 +329,27 @@ config STM32_SPI1
bool "SPI1"
default n
select SPI
+ select STM32_SPI
config STM32_SPI2
bool "SPI2"
default n
select SPI
+ select STM32_SPI
config STM32_SPI3
bool "SPI3"
default n
depends on STM32_STM32F20XX || STM32_STM32F40XX
select SPI
+ select STM32_SPI
config STM32_SPI4
bool "SPI4"
default n
depends on STM32_STM32F10XX
select SPI
+ select STM32_SPI
config STM32_SYSCFG
bool "SYSCFG"
@@ -450,19 +464,18 @@ endmenu
config STM32_ADC
bool
- default y if STM32_ADC1 || STM32_ADC2 || STM32_ADC3
config STM32_DAC
bool
- default y if STM32_DAC1 || STM32_ADC2
config STM32_SPI
bool
- default y if STM32_SPI1 || STM32_SPI2 || STM32_SPI3 || STM32_SPI4
+
+config STM32_I2C
+ bool
config STM32_CAN
bool
- default y if STM32_CAN1 || STM32_CAN2
menu "Alternate Pin Mapping"
@@ -571,10 +584,10 @@ choice
config STM32_CAN1_NO_REMAP
bool "No pin remapping"
-config CONFIG_STM32_CAN1_REMAP1
+config STM32_CAN1_REMAP1
bool "CAN1 alternate pin remapping #1"
-config CONFIG_STM32_CAN1_REMAP2
+config STM32_CAN1_REMAP2
bool "CAN1 alternate pin remapping #2"
endchoice
@@ -1600,6 +1613,46 @@ config STM32_SPI_DMA
endmenu
+menu "I2C Configuration"
+ depends on STM32_I2C
+
+config STM32_I2C_DYNTIMEO
+ bool "Use dynamic timeouts"
+ default n
+ depends on STM32_I2C
+
+config STM32_I2C_DYNTIMEO_USECPERBYTE
+ int "Timeout Microseconds per Byte"
+ default 0
+ depends on STM32_I2C_DYNTIMEO
+
+config STM32_I2C_DYNTIMEO_STARTSTOP
+ int "Timeout for Start/Stop (Milliseconds)"
+ default 5000
+ depends on STM32_I2C_DYNTIMEO
+
+config STM32_I2CTIMEOSEC
+ int "Timeout seconds"
+ default 0
+ depends on STM32_I2C
+
+config STM32_I2CTIMEOMS
+ int "Timeout Milliseconds"
+ default 500
+ depends on STM32_I2C && !STM32_I2C_DYNTIMEO
+
+config STM32_I2CTIMEOTICKS
+ int "Timeout for Done and Stop (ticks)"
+ default 500
+ depends on STM32_I2C && !STM32_I2C_DYNTIMEO
+
+config STM32_I2C_DUTY16_9
+ bool "Frequency with Tlow/Thigh = 16/9 "
+ default n
+ depends on STM32_I2C
+
+endmenu
+
menu "SDIO Configuration"
depends on STM32_SDIO
@@ -1826,13 +1879,13 @@ config STM32_USBHOST_REGDEBUG
default n
depends on USBHOST && STM32_OTGFS
---help---
- Enable very low-level register access debug. Depends on CONFIG_DEBUG.
+ Enable very low-level register access debug. Depends on DEBUG.
config STM32_USBHOST_PKTDUMP
bool "Packet Dump Debug"
default n
depends on USBHOST && STM32_OTGFS
---help---
- Dump all incoming and outgoing USB packets. Depends on CONFIG_DEBUG.
+ Dump all incoming and outgoing USB packets. Depends on DEBUG.
endmenu
diff --git a/nuttx/arch/arm/src/stm32/stm32_i2c.c b/nuttx/arch/arm/src/stm32/stm32_i2c.c
index cbd6f6b14..bd3031b2d 100644
--- a/nuttx/arch/arm/src/stm32/stm32_i2c.c
+++ b/nuttx/arch/arm/src/stm32/stm32_i2c.c
@@ -107,11 +107,11 @@
#if !defined(CONFIG_STM32_I2CTIMEOSEC) && !defined(CONFIG_STM32_I2CTIMEOMS)
# define CONFIG_STM32_I2CTIMEOSEC 0
-# define CONFIG_STM32_I2CTIMEOMS 500 /* Default is 500 milliseconds */
+# define CONFIG_STM32_I2CTIMEOMS 500 /* Default is 500 milliseconds */
#elif !defined(CONFIG_STM32_I2CTIMEOSEC)
# define CONFIG_STM32_I2CTIMEOSEC 0 /* User provided milliseconds */
#elif !defined(CONFIG_STM32_I2CTIMEOMS)
-# define CONFIG_STM32_I2CTIMEOMS 0 /* User provided seconds */
+# define CONFIG_STM32_I2CTIMEOMS 0 /* User provided seconds */
#endif
/* Interrupt wait time timeout in system timer ticks */
@@ -119,6 +119,10 @@
#define CONFIG_STM32_I2CTIMEOTICKS \
(SEC2TICK(CONFIG_STM32_I2CTIMEOSEC) + MSEC2TICK(CONFIG_STM32_I2CTIMEOMS))
+#ifndef CONFIG_STM32_I2C_DYNTIMEO_STARTSTOP
+# define CONFIG_STM32_I2C_DYNTIMEO_STARTSTOP TICK2USEC(CONFIG_STM32_I2CTIMEOTICKS)
+#endif
+
/* On the STM32F103ZE, there is an internal conflict between I2C1 and FSMC. In that
* case, it is necessary to disable FSMC before each I2C1 access and re-enable FSMC
* when the I2C access completes.
@@ -129,6 +133,18 @@
# define I2C1_FSMC_CONFLICT
#endif
+/* Macros to convert a I2C pin to a GPIO output */
+
+#if defined(CONFIG_STM32_STM32F10XX)
+# define I2C_OUTPUT (GPIO_OUTPUT | GPIO_OUTPUT_SET | GPIO_CNF_OUTOD | \
+ GPIO_MODE_50MHz)
+#elif defined(CONFIG_STM32_STM32F20XX) || defined(CONFIG_STM32_STM32F40XX)
+# define I2C_OUTPUT (GPIO_OUTPUT | GPIO_FLOAT | GPIO_OPENDRAIN |\
+ GPIO_SPEED_50MHz | GPIO_OUTPUT_SET)
+#endif
+
+#define MKI2C_OUTPUT(p) (((p) & (GPIO_PORT_MASK | GPIO_PIN_MASK)) | I2C_OUTPUT)
+
/* Debug ****************************************************************************/
/* CONFIG_DEBUG_I2C + CONFIG_DEBUG enables general I2C debug output. */
@@ -196,36 +212,52 @@ struct stm32_trace_s
uint32_t time; /* First of event or first status */
};
+/* I2C Device hardware configuration */
+
+struct stm32_i2c_config_s
+{
+ uint32_t base; /* I2C base address */
+ uint32_t clk_bit; /* Clock enable bit */
+ uint32_t reset_bit; /* Reset bit */
+ uint32_t scl_pin; /* GPIO configuration for SCL as SCL */
+ uint32_t sda_pin; /* GPIO configuration for SDA as SDA */
+#ifndef CONFIG_I2C_POLLED
+ int (*isr)(int, void *); /* Interrupt handler */
+ uint32_t ev_irq; /* Event IRQ */
+ uint32_t er_irq; /* Error IRQ */
+#endif
+};
+
/* I2C Device Private Data */
struct stm32_i2c_priv_s
{
- uint32_t base; /* I2C base address */
- int refs; /* Referernce count */
- sem_t sem_excl; /* Mutual exclusion semaphore */
+ const struct stm32_i2c_config_s *config; /* Port configuration */
+ int refs; /* Referernce count */
+ sem_t sem_excl; /* Mutual exclusion semaphore */
#ifndef CONFIG_I2C_POLLED
- sem_t sem_isr; /* Interrupt wait semaphore */
+ sem_t sem_isr; /* Interrupt wait semaphore */
#endif
- volatile uint8_t intstate; /* Interrupt handshake (see enum stm32_intstate_e) */
+ volatile uint8_t intstate; /* Interrupt handshake (see enum stm32_intstate_e) */
- uint8_t msgc; /* Message count */
- struct i2c_msg_s *msgv; /* Message list */
- uint8_t *ptr; /* Current message buffer */
- int dcnt; /* Current message length */
- uint16_t flags; /* Current message flags */
+ uint8_t msgc; /* Message count */
+ struct i2c_msg_s *msgv; /* Message list */
+ uint8_t *ptr; /* Current message buffer */
+ int dcnt; /* Current message length */
+ uint16_t flags; /* Current message flags */
/* I2C trace support */
#ifdef CONFIG_I2C_TRACE
- int tndx; /* Trace array index */
- uint32_t start_time; /* Time when the trace was started */
+ int tndx; /* Trace array index */
+ uint32_t start_time; /* Time when the trace was started */
/* The actual trace data */
struct stm32_trace_s trace[CONFIG_I2C_NTRACE];
#endif
- uint32_t status; /* End of transfer SR2|SR1 status */
+ uint32_t status; /* End of transfer SR2|SR1 status */
};
/* I2C Device, Instance */
@@ -252,6 +284,9 @@ static inline void stm32_i2c_modifyreg(FAR struct stm32_i2c_priv_s *priv,
uint8_t offset, uint16_t clearbits,
uint16_t setbits);
static inline void stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev);
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+static useconds_t stm32_i2c_tousecs(int msgc, FAR struct i2c_msg_s *msgs);
+#endif /* CONFIG_STM32_I2C_DYNTIMEO */
static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv);
static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv);
static inline void stm32_i2c_sem_post(FAR struct i2c_dev_s *dev);
@@ -263,7 +298,7 @@ static void stm32_i2c_tracenew(FAR struct stm32_i2c_priv_s *priv, uint32_t statu
static void stm32_i2c_traceevent(FAR struct stm32_i2c_priv_s *priv,
enum stm32_trace_e event, uint32_t parm);
static void stm32_i2c_tracedump(FAR struct stm32_i2c_priv_s *priv);
-#endif
+#endif /* CONFIG_I2C_TRACE */
static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv,
uint32_t frequency);
static inline void stm32_i2c_sendstart(FAR struct stm32_i2c_priv_s *priv);
@@ -273,7 +308,7 @@ static inline uint32_t stm32_i2c_getstatus(FAR struct stm32_i2c_priv_s *priv);
#ifdef I2C1_FSMC_CONFLICT
static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv);
static inline void stm32_i2c_enablefsmc(uint32_t ahbenr);
-#endif
+#endif /* I2C1_FSMC_CONFLICT */
static int stm32_i2c_isr(struct stm32_i2c_priv_s * priv);
#ifndef CONFIG_I2C_POLLED
#ifdef CONFIG_STM32_I2C1
@@ -311,9 +346,23 @@ static int stm32_i2c_transfer(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *m
************************************************************************************/
#ifdef CONFIG_STM32_I2C1
-struct stm32_i2c_priv_s stm32_i2c1_priv =
+static const struct stm32_i2c_config_s stm32_i2c1_config =
{
.base = STM32_I2C1_BASE,
+ .clk_bit = RCC_APB1ENR_I2C1EN,
+ .reset_bit = RCC_APB1RSTR_I2C1RST,
+ .scl_pin = GPIO_I2C1_SCL,
+ .sda_pin = GPIO_I2C1_SDA,
+#ifndef CONFIG_I2C_POLLED
+ .isr = stm32_i2c1_isr,
+ .ev_irq = STM32_IRQ_I2C1EV,
+ .er_irq = STM32_IRQ_I2C1ER
+#endif
+};
+
+struct stm32_i2c_priv_s stm32_i2c1_priv =
+{
+ .config = &stm32_i2c1_config,
.refs = 0,
.intstate = INTSTATE_IDLE,
.msgc = 0,
@@ -326,9 +375,23 @@ struct stm32_i2c_priv_s stm32_i2c1_priv =
#endif
#ifdef CONFIG_STM32_I2C2
-struct stm32_i2c_priv_s stm32_i2c2_priv =
+static const struct stm32_i2c_config_s stm32_i2c2_config =
{
.base = STM32_I2C2_BASE,
+ .clk_bit = RCC_APB1ENR_I2C2EN,
+ .reset_bit = RCC_APB1RSTR_I2C2RST,
+ .scl_pin = GPIO_I2C2_SCL,
+ .sda_pin = GPIO_I2C2_SDA,
+#ifndef CONFIG_I2C_POLLED
+ .isr = stm32_i2c2_isr,
+ .ev_irq = STM32_IRQ_I2C2EV,
+ .er_irq = STM32_IRQ_I2C2ER
+#endif
+};
+
+struct stm32_i2c_priv_s stm32_i2c2_priv =
+{
+ .config = &stm32_i2c2_config,
.refs = 0,
.intstate = INTSTATE_IDLE,
.msgc = 0,
@@ -341,9 +404,23 @@ struct stm32_i2c_priv_s stm32_i2c2_priv =
#endif
#ifdef CONFIG_STM32_I2C3
-struct stm32_i2c_priv_s stm32_i2c3_priv =
+static const struct stm32_i2c_config_s stm32_i2c3_config =
{
.base = STM32_I2C3_BASE,
+ .clk_bit = RCC_APB1ENR_I2C3EN,
+ .reset_bit = RCC_APB1RSTR_I2C3RST,
+ .scl_pin = GPIO_I2C3_SCL,
+ .sda_pin = GPIO_I2C3_SDA,
+#ifndef CONFIG_I2C_POLLED
+ .isr = stm32_i2c3_isr,
+ .ev_irq = STM32_IRQ_I2C3EV,
+ .er_irq = STM32_IRQ_I2C3ER
+#endif
+};
+
+struct stm32_i2c_priv_s stm32_i2c3_priv =
+{
+ .config = &stm32_i2c3_config,
.refs = 0,
.intstate = INTSTATE_IDLE,
.msgc = 0,
@@ -355,7 +432,6 @@ struct stm32_i2c_priv_s stm32_i2c3_priv =
};
#endif
-
/* Device Structures, Instantiation */
struct i2c_ops_s stm32_i2c_ops =
@@ -391,7 +467,7 @@ struct i2c_ops_s stm32_i2c_ops =
static inline uint16_t stm32_i2c_getreg(FAR struct stm32_i2c_priv_s *priv,
uint8_t offset)
{
- return getreg16(priv->base + offset);
+ return getreg16(priv->config->base + offset);
}
/************************************************************************************
@@ -405,7 +481,7 @@ static inline uint16_t stm32_i2c_getreg(FAR struct stm32_i2c_priv_s *priv,
static inline void stm32_i2c_putreg(FAR struct stm32_i2c_priv_s *priv, uint8_t offset,
uint16_t value)
{
- putreg16(value, priv->base + offset);
+ putreg16(value, priv->config->base + offset);
}
/************************************************************************************
@@ -420,7 +496,7 @@ static inline void stm32_i2c_modifyreg(FAR struct stm32_i2c_priv_s *priv,
uint8_t offset, uint16_t clearbits,
uint16_t setbits)
{
- modifyreg16(priv->base + offset, clearbits, setbits);
+ modifyreg16(priv->config->base + offset, clearbits, setbits);
}
/************************************************************************************
@@ -440,6 +516,35 @@ static inline void stm32_i2c_sem_wait(FAR struct i2c_dev_s *dev)
}
/************************************************************************************
+ * Name: stm32_i2c_tousecs
+ *
+ * Description:
+ * Return a micro-second delay based on the number of bytes left to be processed.
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+static useconds_t stm32_i2c_tousecs(int msgc, FAR struct i2c_msg_s *msgs)
+{
+ size_t bytecount = 0;
+ int i;
+
+ /* Count the number of bytes left to process */
+
+ for (i = 0; i < msgc; i++)
+ {
+ bytecount += msgs[i].length;
+ }
+
+ /* Then return a number of microseconds based on a user provided scaling
+ * factor.
+ */
+
+ return (useconds_t)(CONFIG_STM32_I2C_DYNTIMEO_USECPERBYTE * bytecount);
+}
+#endif
+
+/************************************************************************************
* Name: stm32_i2c_sem_waitdone
*
* Description:
@@ -480,7 +585,18 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
#if CONFIG_STM32_I2CTIMEOSEC > 0
abstime.tv_sec += CONFIG_STM32_I2CTIMEOSEC;
#endif
-#if CONFIG_STM32_I2CTIMEOMS > 0
+
+ /* Add a value proportional to the number of bytes in the transfer */
+
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+ abstime.tv_nsec += 1000 * stm32_i2c_tousecs(priv->msgc, priv->msgv);
+ if (abstime.tv_nsec > 1000 * 1000 * 1000)
+ {
+ abstime.tv_sec++;
+ abstime.tv_nsec -= 1000 * 1000 * 1000;
+ }
+
+#elif CONFIG_STM32_I2CTIMEOMS > 0
abstime.tv_nsec += CONFIG_STM32_I2CTIMEOMS * 1000 * 1000;
if (abstime.tv_nsec > 1000 * 1000 * 1000)
{
@@ -520,12 +636,21 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
return ret;
}
#else
-static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv )
+static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv)
{
+ uint32_t timeout;
uint32_t start;
uint32_t elapsed;
int ret;
+ /* Get the timeout value */
+
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+ timeout = USEC2TICK(stm32_i2c_tousecs(priv->msgc, priv->msgv));
+#else
+ timeout = CONFIG_STM32_I2CTIMEOTICKS;
+#endif
+
/* Signal the interrupt handler that we are waiting. NOTE: Interrupts
* are currently disabled but will be temporarily re-enabled below when
* sem_timedwait() sleeps.
@@ -533,6 +658,7 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv )
priv->intstate = INTSTATE_WAITING;
start = clock_systimer();
+
do
{
/* Poll by simply calling the timer interrupt handler until it
@@ -548,10 +674,10 @@ static inline int stm32_i2c_sem_waitdone(FAR struct stm32_i2c_priv_s *priv )
/* Loop until the transfer is complete. */
- while (priv->intstate != INTSTATE_DONE && elapsed < CONFIG_STM32_I2CTIMEOTICKS);
+ while (priv->intstate != INTSTATE_DONE && elapsed < timeout);
i2cvdbg("intstate: %d elapsed: %d threshold: %d status: %08x\n",
- priv->intstate, elapsed, CONFIG_STM32_I2CTIMEOTICKS, priv->status);
+ priv->intstate, elapsed, timeout, priv->status);
/* Set the interrupt state back to IDLE */
@@ -573,9 +699,18 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
{
uint32_t start;
uint32_t elapsed;
+ uint32_t timeout;
uint32_t cr1;
uint32_t sr1;
+ /* Select a timeout */
+
+#ifdef CONFIG_STM32_I2C_DYNTIMEO
+ timeout = USEC2TICK(CONFIG_STM32_I2C_DYNTIMEO_STARTSTOP);
+#else
+ timeout = CONFIG_STM32_I2CTIMEOTICKS;
+#endif
+
/* Wait as stop might still be in progress; but stop might also
* be set because of a timeout error: "The [STOP] bit is set and
* cleared by software, cleared by hardware when a Stop condition is
@@ -608,7 +743,7 @@ static inline void stm32_i2c_sem_waitstop(FAR struct stm32_i2c_priv_s *priv)
/* Loop until the stop is complete or a timeout occurs. */
- while (elapsed < CONFIG_STM32_I2CTIMEOTICKS);
+ while (elapsed < timeout);
/* If we get here then a timeout occurred with the STOP condition
* still pending.
@@ -828,7 +963,7 @@ static void stm32_i2c_setclock(FAR struct stm32_i2c_priv_s *priv, uint32_t frequ
{
/* Fast mode speed calculation with Tlow/Thigh = 16/9 */
-#ifdef CONFIG_I2C_DUTY16_9
+#ifdef CONFIG_STM32_I2C_DUTY16_9
speed = (uint16_t)(STM32_PCLK1_FREQUENCY / (frequency * 25));
/* Set DUTY and fast speed bits */
@@ -967,8 +1102,8 @@ static inline uint32_t stm32_i2c_disablefsmc(FAR struct stm32_i2c_priv_s *priv)
/* Is this I2C1 */
-#ifdef CONFIG_STM32_I2C2
- if (priv->base == STM32_I2C1_BASE)
+#if defined(CONFIG_STM32_I2C2) || defined(CONFIG_STM32_I2C3)
+ if (priv->config->base == STM32_I2C1_BASE)
#endif
{
/* Disable FSMC unconditionally */
@@ -1094,6 +1229,14 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv)
{
stm32_i2c_traceevent(priv, I2CEVENT_RCVBYTE, priv->dcnt);
+ /* No interrupts or context switches may occur in the following
+ * sequence. Otherwise, additional bytes may be sent by the
+ * device.
+ */
+
+#ifdef CONFIG_I2C_POLLED
+ irqstate_t state = irqsave();
+#endif
/* Receive a byte */
*priv->ptr++ = stm32_i2c_getreg(priv, STM32_I2C_DR_OFFSET);
@@ -1105,6 +1248,10 @@ static int stm32_i2c_isr(struct stm32_i2c_priv_s *priv)
stm32_i2c_modifyreg(priv, STM32_I2C_CR1_OFFSET, I2C_CR1_ACK, 0);
}
priv->dcnt--;
+
+#ifdef CONFIG_I2C_POLLED
+ irqrestore(state);
+#endif
}
}
@@ -1292,113 +1439,33 @@ static int stm32_i2c_init(FAR struct stm32_i2c_priv_s *priv)
{
/* Power-up and configure GPIOs */
- switch (priv->base)
- {
-#ifdef CONFIG_STM32_I2C1
- case STM32_I2C1_BASE:
-
- /* Enable power and reset the peripheral */
-
- modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_I2C1EN);
-
- modifyreg32(STM32_RCC_APB1RSTR, 0, RCC_APB1RSTR_I2C1RST);
- modifyreg32(STM32_RCC_APB1RSTR, RCC_APB1RSTR_I2C1RST, 0);
-
- /* Configure pins */
-
- if (stm32_configgpio(GPIO_I2C1_SCL) < 0)
- {
- return ERROR;
- }
+ /* Enable power and reset the peripheral */
- if (stm32_configgpio(GPIO_I2C1_SDA) < 0)
- {
- stm32_unconfiggpio(GPIO_I2C1_SCL);
- return ERROR;
- }
+ modifyreg32(STM32_RCC_APB1ENR, 0, priv->config->clk_bit);
+ modifyreg32(STM32_RCC_APB1RSTR, 0, priv->config->reset_bit);
+ modifyreg32(STM32_RCC_APB1RSTR, priv->config->reset_bit, 0);
- /* Attach ISRs */
-
-#ifndef CONFIG_I2C_POLLED
- irq_attach(STM32_IRQ_I2C1EV, stm32_i2c1_isr);
- irq_attach(STM32_IRQ_I2C1ER, stm32_i2c1_isr);
- up_enable_irq(STM32_IRQ_I2C1EV);
- up_enable_irq(STM32_IRQ_I2C1ER);
-#endif
- break;
-#endif
+ /* Configure pins */
-#ifdef CONFIG_STM32_I2C2
- case STM32_I2C2_BASE:
-
- /* Enable power and reset the peripheral */
-
- modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_I2C2EN);
-
- modifyreg32(STM32_RCC_APB1RSTR, 0, RCC_APB1RSTR_I2C2RST);
- modifyreg32(STM32_RCC_APB1RSTR, RCC_APB1RSTR_I2C2RST, 0);
-
- /* Configure pins */
-
- if (stm32_configgpio(GPIO_I2C2_SCL) < 0)
- {
- return ERROR;
- }
-
- if (stm32_configgpio(GPIO_I2C2_SDA) < 0)
- {
- stm32_unconfiggpio(GPIO_I2C2_SCL);
- return ERROR;
- }
-
- /* Attach ISRs */
-
-#ifndef CONFIG_I2C_POLLED
- irq_attach(STM32_IRQ_I2C2EV, stm32_i2c2_isr);
- irq_attach(STM32_IRQ_I2C2ER, stm32_i2c2_isr);
- up_enable_irq(STM32_IRQ_I2C2EV);
- up_enable_irq(STM32_IRQ_I2C2ER);
-#endif
- break;
-#endif
-
-#ifdef CONFIG_STM32_I2C3
- case STM32_I2C3_BASE:
-
- /* Enable power and reset the peripheral */
-
- modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_I2C3EN);
-
- modifyreg32(STM32_RCC_APB1RSTR, 0, RCC_APB1RSTR_I2C3RST);
- modifyreg32(STM32_RCC_APB1RSTR, RCC_APB1RSTR_I2C3RST, 0);
-
- /* Configure pins */
-
- if (stm32_configgpio(GPIO_I2C3_SCL) < 0)
- {
- return ERROR;
- }
-
- if (stm32_configgpio(GPIO_I2C3_SDA) < 0)
- {
- stm32_unconfiggpio(GPIO_I2C3_SCL);
- return ERROR;
- }
+ if (stm32_configgpio(priv->config->scl_pin) < 0)
+ {
+ return ERROR;
+ }
- /* Attach ISRs */
+ if (stm32_configgpio(priv->config->sda_pin) < 0)
+ {
+ stm32_unconfiggpio(priv->config->scl_pin);
+ return ERROR;
+ }
+ /* Attach ISRs */
+
#ifndef CONFIG_I2C_POLLED
- irq_attach(STM32_IRQ_I2C3EV, stm32_i2c3_isr);
- irq_attach(STM32_IRQ_I2C3ER, stm32_i2c3_isr);
- up_enable_irq(STM32_IRQ_I2C3EV);
- up_enable_irq(STM32_IRQ_I2C3ER);
+ irq_attach(priv->config->ev_irq, priv->config->isr);
+ irq_attach(priv->config->er_irq, priv->config->isr);
+ up_enable_irq(priv->config->ev_irq);
+ up_enable_irq(priv->config->er_irq);
#endif
- break;
-#endif
-
- default:
- return ERROR;
- }
/* Set peripheral frequency, where it must be at least 2 MHz for 100 kHz
* or 4 MHz for 400 kHz. This also disables all I2C interrupts.
@@ -1427,42 +1494,23 @@ static int stm32_i2c_deinit(FAR struct stm32_i2c_priv_s *priv)
stm32_i2c_putreg(priv, STM32_I2C_CR1_OFFSET, 0);
- switch (priv->base)
- {
-#ifdef CONFIG_STM32_I2C1
- case STM32_I2C1_BASE:
- stm32_unconfiggpio(GPIO_I2C1_SCL);
- stm32_unconfiggpio(GPIO_I2C1_SDA);
+ /* Unconfigure GPIO pins */
-#ifndef CONFIG_I2C_POLLED
- up_disable_irq(STM32_IRQ_I2C1EV);
- up_disable_irq(STM32_IRQ_I2C1ER);
- irq_detach(STM32_IRQ_I2C1EV);
- irq_detach(STM32_IRQ_I2C1ER);
-#endif
- modifyreg32(STM32_RCC_APB1ENR, RCC_APB1ENR_I2C1EN, 0);
- break;
-#endif
-
-#ifdef CONFIG_STM32_I2C2
- case STM32_I2C2_BASE:
- stm32_unconfiggpio(GPIO_I2C2_SCL);
- stm32_unconfiggpio(GPIO_I2C2_SDA);
+ stm32_unconfiggpio(priv->config->scl_pin);
+ stm32_unconfiggpio(priv->config->sda_pin);
+
+ /* Disable and detach interrupts */
#ifndef CONFIG_I2C_POLLED
- up_disable_irq(STM32_IRQ_I2C2EV);
- up_disable_irq(STM32_IRQ_I2C2ER);
- irq_detach(STM32_IRQ_I2C2EV);
- irq_detach(STM32_IRQ_I2C2ER);
+ up_disable_irq(priv->config->ev_irq);
+ up_disable_irq(priv->config->er_irq);
+ irq_detach(priv->config->ev_irq);
+ irq_detach(priv->config->er_irq);
#endif
- modifyreg32(STM32_RCC_APB1ENR, RCC_APB1ENR_I2C2EN, 0);
- break;
-#endif
-
- default:
- return ERROR;
- }
+ /* Disable clocking */
+
+ modifyreg32(STM32_RCC_APB1ENR, priv->config->clk_bit, 0);
return OK;
}
@@ -1524,14 +1572,13 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
struct stm32_i2c_inst_s *inst = (struct stm32_i2c_inst_s *)dev;
FAR struct stm32_i2c_priv_s *priv = inst->priv;
uint32_t status = 0;
- uint32_t ahbenr;
int errval = 0;
ASSERT(count);
/* Disable FSMC that shares a pin with I2C1 (LBAR) */
- ahbenr = stm32_i2c_disablefsmc(priv);
+ (void)stm32_i2c_disablefsmc(priv);
/* Wait for any STOP in progress. NOTE: If we have to disable the FSMC
* then we cannot do this at the top of the loop, unfortunately. The STOP
@@ -1594,6 +1641,10 @@ static int stm32_i2c_process(FAR struct i2c_dev_s *dev, FAR struct i2c_msg_s *ms
*/
stm32_i2c_clrstart(priv);
+
+ /* Clear busy flag in case of timeout */
+
+ status = priv->status & 0xffff;
}
else
{
@@ -1914,4 +1965,4 @@ int up_i2cuninitialize(FAR struct i2c_dev_s * dev)
return OK;
}
-#endif /* defined(CONFIG_STM32_I2C1) && defined(CONFIG_STM32_I2C2) */
+#endif /* CONFIG_STM32_I2C1 || CONFIG_STM32_I2C2 || CONFIG_STM32_I2C3 */
diff --git a/nuttx/arch/arm/src/stm32/stm32_spi.c b/nuttx/arch/arm/src/stm32/stm32_spi.c
index 40b1a29a0..8de698cd5 100644
--- a/nuttx/arch/arm/src/stm32/stm32_spi.c
+++ b/nuttx/arch/arm/src/stm32/stm32_spi.c
@@ -49,7 +49,7 @@
* 3. Add a calls to up_spiinitialize() in your low level application
* initialization logic
* 4. The handle returned by up_spiinitialize() may then be used to bind the
- * SPI driver to higher level logic (e.g., calling
+ * SPI driver to higher level logic (e.g., calling
* mmcsd_spislotinitialize(), for example, will bind the SPI driver to
* the SPI MMC/SD driver).
*
@@ -881,7 +881,7 @@ static uint32_t spi_setfrequency(FAR struct spi_dev_s *dev, uint32_t frequency)
else
{
/* Less than fPCLK/128. This is as slow as we can go */
-
+
setbits = SPI_CR1_FPCLCKd256; /* 111: fPCLK/256 */
actual = priv->spiclock >> 8;
}
@@ -941,22 +941,22 @@ static void spi_setmode(FAR struct spi_dev_s *dev, enum spi_mode_e mode)
setbits = 0;
clrbits = SPI_CR1_CPOL|SPI_CR1_CPHA;
break;
-
+
case SPIDEV_MODE1: /* CPOL=0; CPHA=1 */
setbits = SPI_CR1_CPHA;
clrbits = SPI_CR1_CPOL;
break;
-
+
case SPIDEV_MODE2: /* CPOL=1; CPHA=0 */
setbits = SPI_CR1_CPOL;
clrbits = SPI_CR1_CPHA;
break;
-
+
case SPIDEV_MODE3: /* CPOL=1; CPHA=1 */
setbits = SPI_CR1_CPOL|SPI_CR1_CPHA;
clrbits = 0;
break;
-
+
default:
return;
}
@@ -1008,7 +1008,7 @@ static void spi_setbits(FAR struct spi_dev_s *dev, int nbits)
setbits = 0;
clrbits = SPI_CR1_DFF;
break;
-
+
case 16:
setbits = SPI_CR1_DFF;
clrbits = 0;
@@ -1111,7 +1111,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
}
/* Exchange one word */
-
+
word = spi_send(dev, word);
/* Is there a buffer to receive the return value? */
@@ -1120,7 +1120,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
{
*dest++ = word;
}
- }
+ }
}
else
{
@@ -1144,7 +1144,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
}
/* Exchange one word */
-
+
word = (uint8_t)spi_send(dev, (uint16_t)word);
/* Is there a buffer to receive the return value? */
@@ -1152,7 +1152,7 @@ static void spi_exchange(FAR struct spi_dev_s *dev, FAR const void *txbuffer,
if (dest)
{
*dest++ = word;
- }
+ }
}
}
}
@@ -1331,7 +1331,7 @@ static void spi_portinitialize(FAR struct stm32_spidev_s *priv)
priv->txdma = stm32_dmachannel(priv->txch);
DEBUGASSERT(priv->rxdma && priv->txdma);
#endif
-
+
/* Enable spi */
spi_modifycr1(priv, SPI_CR1_SPE, 0);
@@ -1360,7 +1360,7 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
FAR struct stm32_spidev_s *priv = NULL;
irqstate_t flags = irqsave();
-
+
#ifdef CONFIG_STM32_SPI1
if (port == 1)
{
@@ -1431,7 +1431,12 @@ FAR struct spi_dev_s *up_spiinitialize(int port)
spi_portinitialize(priv);
}
}
+ else
#endif
+ {
+ spidbg("ERROR: Unsupported SPI port: %d\n", port);
+ return NULL;
+ }
irqrestore(flags);
return (FAR struct spi_dev_s *)priv;