From fbd1db66e13be25d5482d01720dd3ca3b31e281b Mon Sep 17 00:00:00 2001 From: patacongo Date: Wed, 21 Dec 2011 23:31:03 +0000 Subject: [PATCH] STM32 CAN driver now compiles git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4210 7fd9a85b-ad96-42d3-883c-3090e2eb8679 --- .../arm/src/stm32/chip/stm32f40xxx_pinmap.h | 24 +- nuttx/arch/arm/src/stm32/stm32_can.c | 855 +++++++++++++----- nuttx/arch/arm/src/stm32/stm32_pwm.c | 9 +- nuttx/configs/stm3240g-eval/README.txt | 35 + nuttx/configs/stm3240g-eval/include/board.h | 26 + nuttx/include/nuttx/can.h | 3 + 6 files changed, 722 insertions(+), 230 deletions(-) diff --git a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h index 50c49cdbc6..118814dd08 100644 --- a/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h +++ b/nuttx/arch/arm/src/stm32/chip/stm32f40xxx_pinmap.h @@ -122,19 +122,19 @@ /* CAN */ -#define GPIO_CAN1_RX_1 (GPIO_ALT|GPIO_AF9|GPIO_PORTA|GPIO_PIN11) -#define GPIO_CAN1_RX_2 (GPIO_ALT|GPIO_AF9|GPIO_PORTB|GPIO_PIN8) -#define GPIO_CAN1_RX_3 (GPIO_ALT|GPIO_AF9|GPIO_PORTD|GPIO_PIN0) -#define GPIO_CAN1_RX_4 (GPIO_ALT|GPIO_AF9|GPIO_PORTI|GPIO_PIN9) -#define GPIO_CAN1_TX_1 (GPIO_ALT|GPIO_AF9|GPIO_PORTA|GPIO_PIN12) -#define GPIO_CAN1_TX_2 (GPIO_ALT|GPIO_AF9|GPIO_PORTB|GPIO_PIN9) -#define GPIO_CAN1_TX_3 (GPIO_ALT|GPIO_AF9|GPIO_PORTD|GPIO_PIN1) -#define GPIO_CAN1_TX_4 (GPIO_ALT|GPIO_AF9|GPIO_PORTH|GPIO_PIN13) +#define GPIO_CAN1_RX_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN11) +#define GPIO_CAN1_RX_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN8) +#define GPIO_CAN1_RX_3 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN0) +#define GPIO_CAN1_RX_4 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTI|GPIO_PIN9) +#define GPIO_CAN1_TX_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN12) +#define GPIO_CAN1_TX_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN9) +#define GPIO_CAN1_TX_3 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN1) +#define GPIO_CAN1_TX_4 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTH|GPIO_PIN13) -#define GPIO_CAN2_RX_1 (GPIO_ALT|GPIO_AF9|GPIO_PORTB|GPIO_PIN12) -#define GPIO_CAN2_RX_2 (GPIO_ALT|GPIO_AF9|GPIO_PORTB|GPIO_PIN5) -#define GPIO_CAN2_TX_1 (GPIO_ALT|GPIO_AF9|GPIO_PORTB|GPIO_PIN13) -#define GPIO_CAN2_TX_2 (GPIO_ALT|GPIO_AF9|GPIO_PORTB|GPIO_PIN6) +#define GPIO_CAN2_RX_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN12) +#define GPIO_CAN2_RX_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN5) +#define GPIO_CAN2_TX_1 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN13) +#define GPIO_CAN2_TX_2 (GPIO_ALT|GPIO_AF9|GPIO_SPEED_50MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN6) /* DAC -" Once the DAC channelx is enabled, the corresponding GPIO pin * (PA4 or PA5) is automatically connected to the analog converter output diff --git a/nuttx/arch/arm/src/stm32/stm32_can.c b/nuttx/arch/arm/src/stm32/stm32_can.c index 404bf4a1a6..2be900ab24 100755 --- a/nuttx/arch/arm/src/stm32/stm32_can.c +++ b/nuttx/arch/arm/src/stm32/stm32_can.c @@ -88,6 +88,11 @@ # error "CONFIG_CAN2_BAUD is not defined" #endif +/* Delays *******************************************************************/ +/* Time out for INAK bit */ + +#define INAK_TIMEOUT 65535 + /* Debug ********************************************************************/ /* Non-standard debug that may be enabled just for testing CAN */ @@ -110,10 +115,9 @@ struct stm32_can_s { uint8_t port; /* CAN port number (1 or 2) */ - uint8_t cantx; /* CAN TX IRQ number */ uint8_t canrx0; /* CAN RX FIFO 0 IRQ number */ - uint8_t canrx1; /* CAN RX FIFO 1 IRQ number */ - uint8_t cansce; /* CAN RX0 Status change error (SCE) IRQ number */ + uint8_t filter; /* Filter number */ + uint32_t base; /* Base address of the CAN registers */ uint32_t baud; /* Configured baud */ }; @@ -121,6 +125,11 @@ struct stm32_can_s * Private Function Prototypes ****************************************************************************/ +/* CAN Register access */ + +static uint32_t can_getreg(struct stm32_can_s *priv, int offset); +static void can_putreg(struct stm32_can_s *priv, int offset, uint32_t value); + /* CAN driver methods */ static void can_reset(FAR struct can_dev_s *dev); @@ -135,10 +144,13 @@ static bool can_txempty(FAR struct can_dev_s *dev); /* CAN interrupt handling */ -static int can_txinterrupt(int irq, void *context); static int can_rx0interrupt(int irq, void *context); -static int can_rx1interrupt(int irq, void *context); -static int can_sceinterrupt(int irq, void *context); + +/* Initialization */ + +static int can_bittiming(struct stm32_can_s *priv); +static int can_cellinit(struct stm32_can_s *priv); +static int can_filterinit(struct stm32_can_s *priv); /**************************************************************************** * Private Data @@ -162,14 +174,12 @@ static struct stm32_can_s g_can1priv = { .port = 1, #if defined(CONFIG_STM32_STM32F10XX) && !defined(CONFIG_STM32_CONNECTIVITY_LINE) - .cantx = STM32_IRQ_USBHPCANTX, .canrx0 = STM32_IRQ_USBLPCANRX0, #else - .cantx = STM32_IRQ_CAN1TX, .canrx0 = STM32_IRQ_CAN1RX0, #endif - .canrx1 = STM32_IRQ_CAN1RX1, - .cansce = STM32_IRQ_CAN1SCE, + .filter = 0, + .base = STM32_CAN1_BASE, .baud = CONFIG_CAN1_BAUD, }; @@ -184,10 +194,9 @@ static struct can_dev_s g_can1dev = static struct stm32_can_s g_can2priv = { .port = 2, - .cantx = STM32_IRQ_CAN2TX, .canrx0 = STM32_IRQ_CAN2RX0, - .canrx1 = STM32_IRQ_CAN2RX1, - .cansce = STM32_IRQ_CAN2SCE, + .filter = CAN_NFILTERS / 2, + .base = STM32_CAN2_BASE, .baud = CONFIG_CAN2_BAUD, }; @@ -202,6 +211,44 @@ static struct can_dev_s g_can2dev = * Private Functions ****************************************************************************/ +/**************************************************************************** + * Name: can_getreg + * + * Description: + * Read the value of an CAN register. + * + * Input Parameters: + * priv - A reference to the CAN block status + * offset - The offset to the register to read + * + * Returned Value: + * + ****************************************************************************/ + +static uint32_t can_getreg(struct stm32_can_s *priv, int offset) +{ + return getreg32(priv->base + offset); +} + +/**************************************************************************** + * Name: can_getreg + * + * Description: + * Read the value of an CAN register. + * + * Input Parameters: + * priv - A reference to the CAN block status + * offset - The offset to the register to read + * + * Returned Value: + * + ****************************************************************************/ + +static void can_putreg(struct stm32_can_s *priv, int offset, uint32_t value) +{ + putreg32(value, priv->base + offset); +} + /**************************************************************************** * Name: can_reset * @@ -220,29 +267,41 @@ static struct can_dev_s g_can2dev = static void can_reset(FAR struct can_dev_s *dev) { FAR struct stm32_can_s *priv = dev->cd_priv; + uint32_t regval; + uint32_t regbit = 0; irqstate_t flags; - /* Disable interrupts momentary to stop any ongoing CAN event processing */ - - flags = irqsave(); + /* Get the bits in the AHB1RSTR register needed to reset this CAN device */ #ifdef CONFIG_STM32_CAN1 if (priv->port == 1) { -#warning "Missing logic" + regbit = RCC_APB1RSTR_CAN1RST; } else #endif #ifdef CONFIG_STM32_CAN2 if (priv->port == 2) { -#warning "Missing logic" + regbit = RCC_APB1RSTR_CAN2RST; } else #endif { - candbg("Unsupport port %d\n", priv->port); + candbg("Unsupported port %d\n", priv->port); } + + /* Disable interrupts momentary to stop any ongoing CAN event processing and + * to prevent any concurrent access to the AHB1RSTR register. + */ + + flags = irqsave(); + + /* Reset the CAN */ + + regval = getreg32(STM32_RCC_AHB1RSTR); + regval |= regbit; + putreg32(regval, STM32_RCC_AHB1RSTR); irqrestore(flags); } @@ -268,15 +327,26 @@ static int can_setup(FAR struct can_dev_s *dev) FAR struct stm32_can_s *priv = dev->cd_priv; int ret; - /* Attach all CAN interrupts */ + /* CAN cell initialization */ - ret = irq_attach(priv->cantx, can_txinterrupt); + ret = can_cellinit(priv); if (ret < 0) { - candbg("Failed to attach CAN%d TX IRQ (%d)", priv->port, priv->cantx); + candbg("CAN cell initialization failed: %d\n", ret); return ret; } + /* CAN filter initialization */ + + ret = can_filterinit(priv); + if (ret < 0) + { + candbg("CAN filter initialization failed: %d\n", ret); + return ret; + } + + /* Attach only the CAN RX FIFO 0 interrupts. The others are not used */ + ret = irq_attach(priv->canrx0, can_rx0interrupt); if (ret < 0) { @@ -284,28 +354,12 @@ static int can_setup(FAR struct can_dev_s *dev) return ret; } - ret = irq_attach(priv->canrx1, can_rx1interrupt); - if (ret < 0) - { - candbg("Failed to attach CAN%d RX1 IRQ (%d)", priv->port, priv->canrx1); - return ret; - } - - ret = irq_attach(priv->cansce, can_sceinterrupt); - if (ret < 0) - { - candbg("Failed to attach CAN%d SCE IRQ (%d)", priv->port, priv->cansce); - return ret; - } - - /* Enable all interrupts at the NVIC. Interrupts are still disabled in - * the CAN module. Since we coming out of reset here, there should be + /* Enable only the CAN RX FIFO 0 interrupts at the NVIC. Interrupts are + * still disabled in the CAN module. Since we coming out of reset here, + * there should be no pending interrupts. */ - up_enable_irq(priv->cantx); up_enable_irq(priv->canrx0); - up_enable_irq(priv->canrx1); - up_enable_irq(priv->cansce); return OK; } @@ -328,19 +382,13 @@ static void can_shutdown(FAR struct can_dev_s *dev) { FAR struct stm32_can_s *priv = dev->cd_priv; - /* Disable all interrupts */ + /* Disable the RX FIFO 0 interrupt */ - up_disable_irq(priv->cantx); up_disable_irq(priv->canrx0); - up_disable_irq(priv->canrx1); - up_disable_irq(priv->cansce); - /* Detach all interrupts */ + /* Detach the RX FIFO 0 interrupt */ - irq_detach(priv->cantx); irq_detach(priv->canrx0); - irq_detach(priv->canrx1); - irq_detach(priv->cansce); /* And reset the hardware */ @@ -364,24 +412,20 @@ static void can_shutdown(FAR struct can_dev_s *dev) static void can_rxint(FAR struct can_dev_s *dev, bool enable) { FAR struct stm32_can_s *priv = dev->cd_priv; + uint32_t regval; -#ifdef CONFIG_STM32_CAN1 - if (priv->port == 1) + /* Enable/disable the FIFO 0 message pending interrupt */ + + regval = can_getreg(priv, STM32_CAN_IER_OFFSET); + if (enable) { -#warning "Missing logic" + regval |= CAN_IER_FMPIE0; } else -#endif -#ifdef CONFIG_STM32_CAN2 - if (priv->port == 2) { -#warning "Missing logic" - } - else -#endif - { - candbg("Unsupport port %d\n", priv->port); + regval &= ~CAN_IER_FMPIE0; } + can_putreg(priv, STM32_CAN_IER_OFFSET, regval); } /**************************************************************************** @@ -400,25 +444,7 @@ static void can_rxint(FAR struct can_dev_s *dev, bool enable) static void can_txint(FAR struct can_dev_s *dev, bool enable) { - FAR struct stm32_can_s *priv = dev->cd_priv; - -#ifdef CONFIG_STM32_CAN1 - if (priv->port == 1) - { -#warning "Missing logic" - } - else -#endif -#ifdef CONFIG_STM32_CAN2 - if (priv->port == 2) - { -#warning "Missing logic" - } - else -#endif - { - candbg("Unsupport port %d\n", priv->port); - } + /* This driver does not use the TX interrupt */ } /**************************************************************************** @@ -458,7 +484,7 @@ static int can_ioctl(FAR struct can_dev_s *dev, int cmd, unsigned long arg) static int can_remoterequest(FAR struct can_dev_s *dev, uint16_t id) { -#warning "Missing logic" +#warning "Remote request not implemented" return -ENOSYS; } @@ -466,6 +492,16 @@ static int can_remoterequest(FAR struct can_dev_s *dev, uint16_t id) * Name: can_send * * Description: + * Send one can message. + * + * One CAN-message consists of a maximum of 10 bytes. A message is + * composed of at least the first 2 bytes (when there are no data bytes). + * + * Byte 0: Bits 0-7: Bits 3-10 of the 11-bit CAN identifier + * Byte 1: Bits 5-7: Bits 0-2 of the 11-bit CAN identifier + * Bit 4: Remote Tranmission Request (RTR) + * Bits 0-3: Data Length Code (DLC) + * Bytes 2-10: CAN data * * Input Parameters: * dev - An instance of the "upper half" can driver state structure. @@ -475,30 +511,121 @@ static int can_remoterequest(FAR struct can_dev_s *dev, uint16_t id) * ****************************************************************************/ -static int can_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg) +static int can_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg) { FAR struct stm32_can_s *priv = dev->cd_priv; + FAR uint8_t *ptr; + uint32_t regval; + uint32_t tmp; + int dlc; + int txmb; -#ifdef CONFIG_STM32_CAN1 - if (priv->port == 1) + /* Select one empty transmit mailbox */ + + regval = can_getreg(priv, STM32_CAN_TSR_OFFSET); + if ((regval & CAN_TSR_TME0) != 0) { -#warning "Missing logic" + txmb = 0; + } + else if ((regval & CAN_TSR_TME1) != 0) + { + txmb = 1; + } + else if ((regval & CAN_TSR_TME2) != 0) + { + txmb = 2; } else -#endif -#ifdef CONFIG_STM32_CAN2 - if (priv->port == 2) { -#warning "Missing logic" - } - else -#endif - { - candbg("Unsupport port %d\n", priv->port); - return -EINVAL; + candbg("ERROR: No available mailbox\n"); + return -EBUSY; } -#warning "Missing logic" + /* Set up the Id */ + + regval = can_getreg(priv, STM32_CAN_TIR_OFFSET(txmb)); + regval &= ~CAN_TIR_TXRQ; /* Transmit Mailbox Request */ + can_putreg(priv, STM32_CAN_TIR_OFFSET(txmb), regval); + + /* Only standard (11-bit) CAN identifiers are support (the stm 32 + * supports extended, 29-bit identifiers, but this method does not. + * + * Get the 11-bit identifier from the header bits 0-7 and 13-15. + */ + + regval &= ~CAN_TIR_STID_MASK; + regval |= (uint32_t)CAN_ID(msg->cm_hdr) << CAN_TIR_STID_SHIFT; + can_putreg(priv, STM32_CAN_TIR_OFFSET(txmb), regval); + + /* Set up the DLC */ + + dlc = CAN_DLC(msg->cm_hdr); + regval = can_getreg(priv, STM32_CAN_TDTR_OFFSET(txmb)); + regval &= ~CAN_TDTR_DLC_MASK; + regval |= (uint32_t)dlc << CAN_TDTR_DLC_SHIFT; + can_putreg(priv, STM32_CAN_TDTR_OFFSET(txmb), regval); + + /* Set up the data fields */ + + ptr = msg->cm_data; + regval = 0; + + if (dlc > 0) + { + tmp = (uint32_t)*ptr++; + regval = tmp << CAN_TDLR_DATA0_SHIFT; + + if (dlc > 1) + { + tmp = (uint32_t)*ptr++; + regval |= tmp << CAN_TDLR_DATA1_SHIFT; + + if (dlc > 2) + { + tmp = (uint32_t)*ptr++; + regval |= tmp << CAN_TDLR_DATA2_SHIFT; + + if (dlc > 3) + { + tmp = (uint32_t)*ptr++; + regval |= tmp << CAN_TDLR_DATA3_SHIFT; + } + } + } + } + can_putreg(priv, STM32_CAN_TDLR_OFFSET(txmb), regval); + + regval = 0; + if (dlc > 4) + { + tmp = (uint32_t)*ptr++; + regval = tmp << CAN_TDHR_DATA4_SHIFT; + + if (dlc > 5) + { + tmp = (uint32_t)*ptr++; + regval |= tmp << CAN_TDHR_DATA5_SHIFT; + + if (dlc > 6) + { + tmp = (uint32_t)*ptr++; + regval |= tmp << CAN_TDHR_DATA6_SHIFT; + + if (dlc > 7) + { + tmp = (uint32_t)*ptr++; + regval |= tmp << CAN_TDHR_DATA7_SHIFT; + } + } + } + } + can_putreg(priv, STM32_CAN_TDHR_OFFSET(txmb), regval); + + /* Request transmission */ + + regval = can_getreg(priv, STM32_CAN_TIR_OFFSET(txmb)); + regval |= CAN_TIR_TXRQ; /* Transmit Mailbox Request */ + can_putreg(priv, STM32_CAN_TIR_OFFSET(txmb), regval); return OK; } @@ -523,71 +650,26 @@ static int can_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg) static bool can_txempty(FAR struct can_dev_s *dev) { FAR struct stm32_can_s *priv = dev->cd_priv; + uint32_t regval; -#ifdef CONFIG_STM32_CAN1 - if (priv->port == 1) - { -#warning "Missing logic" - } - else -#endif -#ifdef CONFIG_STM32_CAN2 - if (priv->port == 2) - { -#warning "Missing logic" - } - else -#endif - { - candbg("Unsupport port %d\n", priv->port); - return true; - } + /* Return false if any mailbox is unavailable */ -#warning "Missing logic" + regval = can_getreg(priv, STM32_CAN_TSR_OFFSET); + if ((regval & CAN_TSR_TME0) == 0) + { + return false; + } + else if ((regval & CAN_TSR_TME1) == 0) + { + return false; + } + else if ((regval & CAN_TSR_TME2) == 0) + { + return false; + } return true; } -/**************************************************************************** - * Name: can_txinterrupt - * - * Description: - * CAN TX interrupt handler - * - * Input Parameters: - * dev - An instance of the "upper half" can driver state structure. - * - * Returned Value: - * Zero on success; a negated errno on failure - * - ****************************************************************************/ - -static int can_txinterrupt(int irq, void *context) -{ - FAR struct stm32_can_s *priv; - -#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) - if (g_can1priv.cantx == irq) - { - priv = &g_can1priv; - } - else if (g_can2priv.cantx == irq) - { - priv = &g_can2priv; - } - else - { - PANIC(OSERR_UNEXPECTEDISR); - } -#elif defined(CONFIG_STM32_CAN1) - priv = &g_can1priv; -#else /* defined(CONFIG_STM32_CAN2) */ - priv = &g_can2priv; -#endif - -#warning "Missing logic" - return OK; -} - /**************************************************************************** * Name: can_rx0interrupt * @@ -604,111 +686,429 @@ static int can_txinterrupt(int irq, void *context) static int can_rx0interrupt(int irq, void *context) { + FAR struct can_dev_s *dev = NULL; FAR struct stm32_can_s *priv; + uint8_t data[CAN_MAXDATALEN]; + uint32_t regval; + int id; + int rtr; + int dlc; + int ret; #if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) if (g_can1priv.canrx0 == irq) { - priv = &g_can1priv; + dev = &g_can1dev; } else if (g_can2priv.canrx0 == irq) { - priv = &g_can2priv; + dev = &g_can2dev; } else { PANIC(OSERR_UNEXPECTEDISR); } #elif defined(CONFIG_STM32_CAN1) - priv = &g_can1priv; + dev = &g_can1dev; #else /* defined(CONFIG_STM32_CAN2) */ - priv = &g_can2priv; + dev = &g_can2dev; #endif + priv = dev->cd_priv; -#warning "Missing logic" - return OK; + /* Get the CAN identifier. Only standard 11-bit IDs are supported */ + + regval = can_getreg(priv, STM32_CAN_RI0R_OFFSET); + if ((regval & CAN_RIR_IDE) != 0) + { + canlldbg("ERROR: Received message with extended identifier. Dropped\n"); + ret = -ENOSYS; + goto errout; + } + + id = (regval & CAN_RIR_STID_MASK) >> CAN_RIR_STID_SHIFT; + + /* Get the Remote Transmission Request (RTR) */ + + rtr = (regval & CAN_RIR_RTR) != 0 ? 1 : 0; + + /* Get the DLC */ + + regval = can_getreg(priv, STM32_CAN_RDT0R_OFFSET); + dlc = (regval & CAN_RDTR_DLC_MASK) >> CAN_RDTR_DLC_SHIFT; + + /* Save the message data */ + + regval = can_getreg(priv, STM32_CAN_RDL0R_OFFSET); + data[0] = (regval & CAN_RDLR_DATA0_MASK) >> CAN_RDLR_DATA0_SHIFT; + data[1] = (regval & CAN_RDLR_DATA1_MASK) >> CAN_RDLR_DATA1_SHIFT; + data[2] = (regval & CAN_RDLR_DATA2_MASK) >> CAN_RDLR_DATA2_SHIFT; + data[3] = (regval & CAN_RDLR_DATA3_MASK) >> CAN_RDLR_DATA3_SHIFT; + + regval = can_getreg(priv, STM32_CAN_RDH0R_OFFSET); + data[4] = (regval & CAN_RDHR_DATA4_MASK) >> CAN_RDHR_DATA4_SHIFT; + data[5] = (regval & CAN_RDHR_DATA5_MASK) >> CAN_RDHR_DATA4_SHIFT; + data[6] = (regval & CAN_RDHR_DATA6_MASK) >> CAN_RDHR_DATA4_SHIFT; + data[7] = (regval & CAN_RDHR_DATA7_MASK) >> CAN_RDHR_DATA4_SHIFT; + + /* Provide the data to the upper half driver */ + + ret = can_receive(dev, (uint16_t)CAN_MSG(id, rtr, dlc), data); + + /* Release the FIFO0 */ + +errout: + regval = can_getreg(priv, STM32_CAN_RF0R_OFFSET); + regval |= CAN_RFR_RFOM; + can_putreg(priv, STM32_CAN_RF0R_OFFSET, regval); + return ret; } /**************************************************************************** - * Name: can_rx1interrupt + * Name: can_bittiming * * Description: - * CAN FIFO 1 interrupt handler + * Set the CAN bit timing register (BTR) based on the configured BAUD. * - * Input Parameters: - * dev - An instance of the "upper half" can driver state structure. + * "The bit timing logic monitors the serial bus-line and performs sampling + * and adjustment of the sample point by synchronizing on the start-bit edge + * and resynchronizing on the following edges. + * + * "Its operation may be explained simply by splitting nominal bit time into + * three segments as follows: + * + * 1. "Synchronization segment (SYNC_SEG): a bit change is expected to occur + * within this time segment. It has a fixed length of one time quantum + * (1 x tCAN). + * 2. "Bit segment 1 (BS1): defines the location of the sample point. It + * includes the PROP_SEG and PHASE_SEG1 of the CAN standard. Its duration + * is programmable between 1 and 16 time quanta but may be automatically + * lengthened to compensate for positive phase drifts due to differences + * in the frequency of the various nodes of the network. + * 3. "Bit segment 2 (BS2): defines the location of the transmit point. It + * represents the PHASE_SEG2 of the CAN standard. Its duration is + * programmable between 1 and 8 time quanta but may also be automatically + * shortened to compensate for negative phase drifts." + * + * Pictorially: + * + * |<----------------- NOMINAL BIT TIME ----------------->| + * |<- SYNC_SEG ->|<------ BS1 ------>|<------ BS2 ------>| + * |<---- Tq ---->|<----- Tbs1 ------>|<----- Tbs2 ------>| + * + * Where + * Tbs1 is the duration of the BS1 segment + * Tbs2 is the duration of the BS2 segment + * Tq is the "Time Quantum" + * + * Relationships: + * + * baud = 1 / bit_time + * bit_time = Tq + Tbs1 + Tbs2 + * Tbs1 = Tq * ts1 + * Tbs2 = Tq * ts2 + * Tq = brp * Tpclk1 + * + * Where: + * Tpclk1 is the period of the APB1 clock (PCLK1). + * + * Input Parameter: + * priv - A reference to the CAN block status * * Returned Value: * Zero on success; a negated errno on failure * ****************************************************************************/ -static int can_rx1interrupt(int irq, void *context) +static int can_bittiming(struct stm32_can_s *priv) { - FAR struct stm32_can_s *priv; + uint32_t tmp; + uint32_t brp; + uint32_t ts1; + uint32_t ts2; + int candidate; + int diff; -#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) - if (g_can1priv.canrx1 == irq) - { - priv = &g_can1priv; - } - else if (g_can2priv.canrx1 == irq) - { - priv = &g_can2priv; - } - else - { - PANIC(OSERR_UNEXPECTEDISR); - } -#elif defined(CONFIG_STM32_CAN1) - priv = &g_can1priv; -#else /* defined(CONFIG_STM32_CAN2) */ - priv = &g_can2priv; -#endif + canvdbg("PCLK1: %d baud: %d\n" ,STM32_PCLK1_FREQUENCY, priv->baud); -#warning "Missing logic" - return OK; + /* Loop trying different values of ts1 until we get a solution with the + * ts1 near ts2 and both values within range. + * + * Example: + * PCLK1 = 42,000,000 baud = 1,000,000 : tmp = 13 + */ + + tmp = STM32_PCLK1_FREQUENCY / 3 / priv->baud - 1; + + for (candidate = 1, ts1 = 17, diff = 16; candidate <= 16; candidate++) + { + /* Then calculate the new ts2 value corresponding to this candidate: + * + * Example: + * ... + * PCLK1 = 42,000,000 baud = 1,000,000 tmp = 13 candidate = 4 : ts2 = 9 + * PCLK1 = 42,000,000 baud = 1,000,000 tmp = 13 candidate = 5 : ts2 = 8 + * PCLK1 = 42,000,000 baud = 1,000,000 tmp = 13 candidate = 6 : ts2 = 7 + * ... + */ + + ts2 = tmp - candidate; + + /* Break out if ts2 is too small (it will only get smaller on the following + * passes. + */ + + if (ts2 < 1) + { + break; + } + + /* Is ts2 within its upper range. No then keep looping because it + * will get smaller. + */ + + else if (ts2 <= 8) + { + /* In range is is the best so far? */ + + int tmpdiff = candidate - ts2; + if (tmpdiff < 0) + { + tmpdiff = -tmpdiff; + } + + if (tmpdiff < diff) + { + diff = tmpdiff; + ts1 = candidate; + } + } + } + + /* Check for errors */ + + if (ts1 > 16) + { + /* If this happens, it means that there is a bug in the algorithm */ + + candbg("Could not find a value for TS1/2\n"); + return -EINVAL; + } + + /* Calculate the BRP value would support the selected values of ts1 value and ts2: + * + * Example: + * PCLK1 = 42,000,000 baud = 1,000,000 ts1 = 6 ts2 = 7 : tmp = 3,000,000 brp = 3 + */ + + tmp = STM32_PCLK1_FREQUENCY / (ts1 + ts2 + 1); + brp = (tmp + (priv->baud - 1)) / priv->baud; + + /* Check for errors */ + + if (brp > 1024) + { + /* If this happens, it means that there is a bug in the algorithm */ + + candbg("BRP is out of range: TS1: %d TS2: %d BRP: %d\n", ts1, ts2, brp); + return -EINVAL; + } + canvdbg("TS1: %d TS2: %d BRP: %d\n", ts1, ts2, brp); + + /* Configure bit timing. This also does the the following, less obvious + * things: + * + * - Disables silent mode. + * - Disables loopback mode. + * + * NOTE that for the time being, SJW is set to 1 just because I don't + * know any better. + */ + + tmp = ((brp - 1) << CAN_BTR_BRP_SHIFT) | ((ts1 - 1) << CAN_BTR_TS1_SHIFT) | + ((ts2 - 1) << CAN_BTR_TS2_SHIFT) | ((1 - 1) << CAN_BTR_SJW_SHIFT); + can_putreg(priv, STM32_CAN_BTR_OFFSET, tmp); + return OK; } /**************************************************************************** - * Name: can_sceinterrupt + * Name: can_cellinit * * Description: - * CAN Status Change Error (SCE) interrupt handler + * CAN cell initialization * - * Input Parameters: - * dev - An instance of the "upper half" can driver state structure. + * Input Parameter: + * priv - A pointer to the private data structure for this CAN block * * Returned Value: - * Zero on success; a negated errno on failure + * Zero on success; a negated errno value on failure. * ****************************************************************************/ -static int can_sceinterrupt(int irq, void *context) +static int can_cellinit(struct stm32_can_s *priv) { - FAR struct stm32_can_s *priv; + volatile uint32_t timeout; + uint32_t regval; + int ret; -#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2) - if (g_can1priv.cansce == irq) - { - priv = &g_can1priv; - } - else if (g_can2priv.cansce == irq) - { - priv = &g_can2priv; - } - else - { - PANIC(OSERR_UNEXPECTEDISR); - } -#elif defined(CONFIG_STM32_CAN1) - priv = &g_can1priv; -#else /* defined(CONFIG_STM32_CAN2) */ - priv = &g_can2priv; -#endif + /* Exit from sleep mode */ -#warning "Missing logic" - return OK; + regval = can_getreg(priv, STM32_CAN_MCR_OFFSET); + regval &= ~CAN_MCR_SLEEP; + can_putreg(priv, STM32_CAN_MCR_OFFSET, regval); + + /* Enter initialization mode */ + + regval = can_getreg(priv, STM32_CAN_MCR_OFFSET); + regval |= CAN_MCR_INRQ; + can_putreg(priv, STM32_CAN_MCR_OFFSET, regval); + + /* Wait until initialization mode is acknowledged */ + + for (timeout = INAK_TIMEOUT; timeout > 0; timeout++) + { + regval = can_getreg(priv, STM32_CAN_MSR_OFFSET); + if ((regval & CAN_MSR_INAK) != 0) + { + /* We are in initialization mode */ + + break; + } + } + + /* Check for a timeout */ + + if (timeout < 1) + { + candbg("ERROR: Timed out waiting to enter intialization mode\n"); + return -ETIMEDOUT; + } + + /* Disable the following modes: + * + * - Time triggered communication mode + * - Automatic bus-off management + * - Automatic wake-up mode + * - No automatic retransmission + * - Receive FIFO locked mode + * - Transmit FIFO priority + */ + + regval = can_getreg(priv, STM32_CAN_MCR_OFFSET); + regval &= ~(CAN_MCR_TXFP | CAN_MCR_RFLM | CAN_MCR_NART | CAN_MCR_AWUM | CAN_MCR_ABOM | CAN_MCR_TTCM); + can_putreg(priv, STM32_CAN_MCR_OFFSET, regval); + + /* Configure bit timing. */ + + ret = can_bittiming(priv); + if (ret < 0) + { + candbg("ERROR: Failed to set bit timing: %d\n", ret); + return ret; + } + + /* Exit initialization mode */ + + regval = can_getreg(priv, STM32_CAN_MCR_OFFSET); + regval &= ~CAN_MCR_INRQ; + can_putreg(priv, STM32_CAN_MCR_OFFSET, regval); + + /* Wait until initialization mode is acknowledged */ + + for (timeout = INAK_TIMEOUT; timeout > 0; timeout++) + { + regval = can_getreg(priv, STM32_CAN_MSR_OFFSET); + if ((regval & CAN_MSR_INAK) == 0) + { + /* We are out of initialization mode */ + + break; + } + } + + /* Check for a timeout */ + + if (timeout < 1) + { + candbg("ERROR: Timed out waiting to exit intialization mode\n"); + return -ETIMEDOUT; + } + return OK; +} + +/**************************************************************************** + * Name: can_filterinit + * + * Description: + * CAN filter initialization + * + * Input Parameter: + * priv - A pointer to the private data structure for this CAN block + * + * Returned Value: + * Zero on success; a negated errno value on failure. + * + ****************************************************************************/ + +static int can_filterinit(struct stm32_can_s *priv) +{ + uint32_t regval; + uint32_t bitmask; + + canvdbg("CAN%d filter: %d\n", priv->port, priv->filter); + + /* Get the bitmask associated with the filter used by this CAN block */ + + bitmask = ((uint32_t)1) << priv->filter; + + /* Enter filter intialization mode */ + + regval = can_getreg(priv, STM32_CAN_FMR_OFFSET); + regval |= CAN_FMR_FINIT; + can_putreg(priv, STM32_CAN_FMR_OFFSET, regval); + + /* Disable the filter */ + + regval = can_getreg(priv, STM32_CAN_FA1R_OFFSET); + regval &= ~bitmask; + can_putreg(priv, STM32_CAN_FA1R_OFFSET, regval); + + /* Select the 32-bit scale for the filter */ + + regval = can_getreg(priv, STM32_CAN_FS1R_OFFSET); + regval |= bitmask; + can_putreg(priv, STM32_CAN_FS1R_OFFSET, regval); + + /* There are 14 or 28 filter banks (depending) on the device. Each filter bank is + * composed of two 32-bit registers, CAN_FiR: + */ + + can_putreg(priv, STM32_CAN_FIR_OFFSET(priv->filter, 0), 0); + can_putreg(priv, STM32_CAN_FIR_OFFSET(priv->filter, 1), 0); + + /* Set Id/Mask mode for the filter */ + + regval = can_getreg(priv, STM32_CAN_FM1R_OFFSET); + regval &= ~bitmask; + can_putreg(priv, STM32_CAN_FM1R_OFFSET, regval); + + /* Assign FIFO 0 for the filter */ + + regval = can_getreg(priv, STM32_CAN_FFA1R_OFFSET); + regval &= ~bitmask; + can_putreg(priv, STM32_CAN_FFA1R_OFFSET, regval); + + /* Enable the filter */ + + regval = can_getreg(priv, STM32_CAN_FA1R_OFFSET); + regval |= bitmask; + can_putreg(priv, STM32_CAN_FA1R_OFFSET, regval); + + /* Exit filter initialization mode */ + + regval = can_getreg(priv, STM32_CAN_FMR_OFFSET); + regval &= ~CAN_FMR_FINIT; + can_putreg(priv, STM32_CAN_FMR_OFFSET, regval); + return OK; } /**************************************************************************** @@ -733,26 +1133,47 @@ FAR struct can_dev_s *up_caninitialize(int port) { struct can_dev_s *dev = NULL; + /* NOTE: Peripherical clocking for CAN1 and/or CAN2 was already provided + * by stm32_clockconfig() early in the reset sequence. + */ + #ifdef CONFIG_STM32_CAN1 if( port == 1 ) { + /* Select the CAN1 device structure */ + dev = &g_can1dev; + + /* Configure CAN1 pins. The ambiguous settings in the stm32*_pinmap.h + * file must have been disambiguated in the board.h file. + */ + + stm32_configgpio(GPIO_CAN1_RX); + stm32_configgpio(GPIO_CAN1_TX); } else #endif #ifdef CONFIG_STM32_CAN2 if ( port ==2 ) { + /* Select the CAN2 device structure */ + dev = &g_can2dev; + + /* Configure CAN2 pins. The ambiguous settings in the stm32*_pinmap.h + * file must have been disambiguated in the board.h file. + */ + + stm32_configgpio(GPIO_CAN2_RX); + stm32_configgpio(GPIO_CAN2_TX); } else #endif { - candbg("Unsupport port %d\n", priv->port); + candbg("Unsupported port %d\n", priv->port); return NULL; } -#warning "Missing logic" return dev; } diff --git a/nuttx/arch/arm/src/stm32/stm32_pwm.c b/nuttx/arch/arm/src/stm32/stm32_pwm.c index fb3323d7ea..8261b07ad9 100644 --- a/nuttx/arch/arm/src/stm32/stm32_pwm.c +++ b/nuttx/arch/arm/src/stm32/stm32_pwm.c @@ -815,10 +815,10 @@ static int pwm_start(FAR struct pwm_lowerhalf_s *dev, FAR const struct pwm_info_ static int pwm_stop(FAR struct pwm_lowerhalf_s *dev) { FAR struct stm32_pwmtimer_s *priv = (FAR struct stm32_pwmtimer_s *)dev; - uint32_t resetbit; uint32_t regaddr; uint32_t regval; + irqstate_t flags; pwmvdbg("TIM%d\n", priv->timid); @@ -898,6 +898,12 @@ static int pwm_stop(FAR struct pwm_lowerhalf_s *dev) #endif } + /* Disable interrupts momentary to stop any ongoing timer processing and + * to prevent any concurrent access to the reset register. + */ + + flags = irqsave(); + /* Reset the timer - stopping the output and putting the timer back * into a state where pwm_start() can be called. */ @@ -908,6 +914,7 @@ static int pwm_stop(FAR struct pwm_lowerhalf_s *dev) regval &= ~resetbit; putreg32(regval, regaddr); + irqrestore(flags); pwmvdbg("regaddr: %08x resetbit: %08x\n", regaddr, resetbit); pwm_dumpregs(priv, "After stop"); diff --git a/nuttx/configs/stm3240g-eval/README.txt b/nuttx/configs/stm3240g-eval/README.txt index 8813ac821f..5bed82cc85 100755 --- a/nuttx/configs/stm3240g-eval/README.txt +++ b/nuttx/configs/stm3240g-eval/README.txt @@ -15,6 +15,7 @@ Contents - LEDs - Ethernet - PWM + - CAN - Configurations Development Environment @@ -220,6 +221,40 @@ FSMC must be disabled in this case! PD13 is available at: TFT LCD Connector, CN19, pin 17 -- not available without removing the LCD. Motor Control Connector CN15, pin 33 -- not available unless you bridge SB14. +CAN +=== + +Connector 10 (CN10) is DB-9 male connector that can be used with CAN1 or CAN2. + + JP10 connects CAN1_RX or CAN2_RX to the CAN transceiver + JP3 connects CAN1_TX or CAN2_TX to the CAN transceiver + +CAN signals are then available on CN10 pins: + + CN10 Pin 7 = CANH + CN10 Pin 2 = CANL + +Mapping to STM32 GPIO pins: + + PD0 = FSMC_D2 & CAN1_RX + PD1 = FSMC_D3 & CAN1_TX + PB13 = ULPI_D6 & CAN2_TX + PB5 = ULPI_D7 & CAN2_RX + +Configuration Options: + + CONFIG_CAN - Enables CAN support (one or both of CONFIG_STM32_CAN1 or + CONFIG_STM32_CAN2 must also be defined) + CONFIG_CAN_FIFOSIZE - The size of the circular buffer of CAN messages. + Default: 8 + CONFIG_CAN_NPENDINGRTR - The size of the list of pending RTR requests. + Default: 4 + + CONFIG_STM32_CAN1 - Enable support for CAN1 + CONFIG_CAN1_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN1 is defined. + CONFIG_STM32_CAN2 - Enable support for CAN1 + CONFIG_CAN2_BAUD - CAN1 BAUD rate. Required if CONFIG_STM32_CAN2 is defined. + STM3240G-EVAL-specific Configuration Options ============================================ diff --git a/nuttx/configs/stm3240g-eval/include/board.h b/nuttx/configs/stm3240g-eval/include/board.h index 0f6f2fca10..caf93e54f7 100755 --- a/nuttx/configs/stm3240g-eval/include/board.h +++ b/nuttx/configs/stm3240g-eval/include/board.h @@ -301,6 +301,32 @@ #define GPIO_TIM4_CH2 GPIO_TIM4_CH2_2 +/* CAN + * + * Connector 10 (CN10) is DB-9 male connector that can be used with CAN1 or CAN2. + * + * JP10 connects CAN1_RX or CAN2_RX to the CAN transceiver + * JP3 connects CAN1_TX or CAN2_TX to the CAN transceiver + * + * CAN signals are then available on CN10 pins: + * + * CN10 Pin 7 = CANH + * CN10 Pin 2 = CANL + * + * Mapping to STM32 GPIO pins: + * + * PD0 = FSMC_D2 & CAN1_RX + * PD1 = FSMC_D3 & CAN1_TX + * PB13 = ULPI_D6 & CAN2_TX + * PB5 = ULPI_D7 & CAN2_RX + */ + +#define GPIO_CAN1_RX GPIO_CAN1_RX_3 +#define GPIO_CAN1_TX GPIO_CAN1_TX_3 + +#define GPIO_CAN2_RX GPIO_CAN2_RX_2 +#define GPIO_CAN2_TX GPIO_CAN2_TX_1 + /************************************************************************************ * Public Data ************************************************************************************/ diff --git a/nuttx/include/nuttx/can.h b/nuttx/include/nuttx/can.h index f87c2eac47..d839bbb171 100644 --- a/nuttx/include/nuttx/can.h +++ b/nuttx/include/nuttx/can.h @@ -89,11 +89,14 @@ /* CAN message support */ #define CAN_MAXDATALEN 8 + #define CAN_ID(hdr) ((uint16_t)(hdr) >> 5) #define CAN_RTR(hdr) (((hdr) & 0x0010) != 0) #define CAN_DLC(hdr) ((hdr) & 0x0f) #define CAN_MSGLEN(hdr) (sizeof(struct can_msg_s) - (CAN_MAXDATALEN - CAN_DLC(hdr))) +#define CAN_MSG(id, rtr, dlc) ((uint16_t)id << 5 | (uint16_t)rtr << 4 | (uint16_t)dlc) + /* Built-in ioctl commands * * CANIOCTL_RTR: Send the remote transmission request and wait for the response.