summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-10 22:29:39 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-01-10 22:29:39 +0000
commit2878c08369c4ac8819e0f6530784f22509bcab92 (patch)
tree92567fed48fbb8c44552b220ab80d17ec19cfba0 /nuttx
parentb45972d006d34d588ef0bde2ebffb2de5843b0fa (diff)
downloadpx4-nuttx-2878c08369c4ac8819e0f6530784f22509bcab92.tar.gz
px4-nuttx-2878c08369c4ac8819e0f6530784f22509bcab92.tar.bz2
px4-nuttx-2878c08369c4ac8819e0f6530784f22509bcab92.zip
Fix LPC17 CAN driver; TX must be interrupt driven
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4290 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rwxr-xr-xnuttx/arch/arm/src/lpc17xx/lpc17_can.c118
-rwxr-xr-xnuttx/configs/stm3240g-eval/nsh/defconfig10
-rw-r--r--nuttx/drivers/can.c26
-rw-r--r--nuttx/include/nuttx/can.h7
4 files changed, 116 insertions, 45 deletions
diff --git a/nuttx/arch/arm/src/lpc17xx/lpc17_can.c b/nuttx/arch/arm/src/lpc17xx/lpc17_can.c
index eab57d2a8..3539ce4af 100755
--- a/nuttx/arch/arm/src/lpc17xx/lpc17_can.c
+++ b/nuttx/arch/arm/src/lpc17xx/lpc17_can.c
@@ -203,6 +203,7 @@ static void can_txint(FAR struct can_dev_s *dev, bool enable);
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);
static int can_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg);
+static bool can_txready(FAR struct can_dev_s *dev);
static bool can_txempty(FAR struct can_dev_s *dev);
/* CAN interrupts */
@@ -228,6 +229,7 @@ static const struct can_ops_s g_canops =
.co_ioctl = can_ioctl,
.co_remoterequest = can_remoterequest,
.co_send = can_send,
+ .co_txready = can_txready,
.co_txempty = can_txempty,
};
@@ -739,6 +741,19 @@ static int can_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg)
regval = can_getreg(priv, LPC17_CAN_SR_OFFSET);
if ((regval & CAN_SR_TBS1) != 0)
{
+ /* Make sure that buffer 1 TX interrupts are enabled BEFORE sending the
+ * message. The TX interrupt is generated when the TBSn bit in CANxSR
+ * goes from 0 to 1 when the TIEn bit in CANxIER is 1. If we don't
+ * enable it now, we may miss the TIE1 interrupt.
+ *
+ * NOTE: The IER is also modified from the interrupt handler, but the
+ * following is safe because interrupts are disabled here.
+ */
+
+ regval = can_getreg(priv, LPC17_CAN_IER_OFFSET);
+ regval |= CAN_IER_TIE1;
+ can_putreg(priv, LPC17_CAN_IER_OFFSET, regval);
+
/* Set up the transfer */
can_putreg(priv, LPC17_CAN_TFI1_OFFSET, tfi);
@@ -753,16 +768,23 @@ static int can_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg)
#else
can_putreg(priv, LPC17_CAN_CMR_OFFSET, CAN_CMR_STB1 | CAN_CMR_TR);
#endif
-
- /* Tell the caller that the transfer is done. It isn't, but we have
- * more transmit buffers and this can speed things up.
- */
-
- can_txdone(dev);
}
else if ((regval & CAN_SR_TBS2) != 0)
{
- /* Set up the transfer */
+ /* Make sure that buffer 2 TX interrupts are enabled BEFORE sending the
+ * message. The TX interrupt is generated when the TBSn bit in CANxSR
+ * goes from 0 to 1 when the TIEn bit in CANxIER is 1. If we don't
+ * enable it now, we may miss the TIE2 interrupt.
+ *
+ * NOTE: The IER is also modified from the interrupt handler, but the
+ * following is safe because interrupts are disabled here.
+ */
+
+ regval = can_getreg(priv, LPC17_CAN_IER_OFFSET);
+ regval |= CAN_IER_TIE2;
+ can_putreg(priv, LPC17_CAN_IER_OFFSET, regval);
+
+ /* Set up the transfer */
can_putreg(priv, LPC17_CAN_TFI2_OFFSET, tfi);
can_putreg(priv, LPC17_CAN_TID2_OFFSET, tid);
@@ -776,29 +798,20 @@ static int can_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg)
#else
can_putreg(priv, LPC17_CAN_CMR_OFFSET, CAN_CMR_STB2 | CAN_CMR_TR);
#endif
-
- /* Tell the caller that the transfer is done. It isn't, but we have
- * more transmit buffers and this can speed things up.
- */
-
- can_txdone(dev);
}
else if ((regval & CAN_SR_TBS3) != 0)
{
- /* We have no more buffers. We will make the caller wait. First, make
- * sure that all buffer 3 interrupts are enabled BEFORE sending the
- * message. The TX interrupt is generated TBSn bit in CANxSR goes from 0
- * to 1 when the TIEn bit in CANxIER is 1. If we don't enable it now,
- * we will miss the TIE3 interrupt. We enable ALL TIE interrupts here
- * because we don't care which one finishes: When first one finishes it
- * means that a transmit buffer is again available.
+ /* Make sure that buffer 3 TX interrupts are enabled BEFORE sending the
+ * message. The TX interrupt is generated when the TBSn bit in CANxSR
+ * goes from 0 to 1 when the TIEn bit in CANxIER is 1. If we don't
+ * enable it now, we may miss the TIE3 interrupt.
*
* NOTE: The IER is also modified from the interrupt handler, but the
* following is safe because interrupts are disabled here.
*/
regval = can_getreg(priv, LPC17_CAN_IER_OFFSET);
- regval |= (CAN_IER_TIE1 | CAN_IER_TIE2 | CAN_IER_TIE3);
+ regval |= CAN_IER_TIE3;
can_putreg(priv, LPC17_CAN_IER_OFFSET, regval);
/* Set up the transfer */
@@ -827,6 +840,27 @@ static int can_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg)
}
/****************************************************************************
+ * Name: can_txready
+ *
+ * Description:
+ * Return true if the CAN hardware can accept another TX message.
+ *
+ * Input Parameters:
+ * dev - An instance of the "upper half" can driver state structure.
+ *
+ * Returned Value:
+ * True is the CAN hardware is ready to accept another TX message.
+ *
+ ****************************************************************************/
+
+static bool can_txready(FAR struct can_dev_s *dev)
+{
+ FAR struct up_dev_s *priv = (FAR struct up_dev_s *)dev->cd_priv;
+ uint32_t regval = can_getreg(priv, LPC17_CAN_SR_OFFSET);
+ return ((regval & (CAN_SR_TBS1 | CAN_SR_TBS2 | CAN_SR_TBS3)) != 0);
+}
+
+/****************************************************************************
* Name: can_txempty
*
* Description:
@@ -840,7 +874,7 @@ static int can_send(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg)
* dev - An instance of the "upper half" can driver state structure.
*
* Returned Value:
- * Zero on success; a negated errno on failure
+ * True is there are no pending TX transfers in the CAN hardware.
*
****************************************************************************/
@@ -907,16 +941,44 @@ static void can_interrupt(FAR struct can_dev_s *dev)
can_receive(dev, hdr, (uint8_t *)data);
}
- /* Check for a transmit interrupt from buffer 1, 2, or 3 meaning that at
- * least one TX is complete and that at least one TX buffer is available.
- */
+ /* Check for TX buffer 1 complete */
+
+ if ((regval & CAN_ICR_TI1) != 0)
+ {
+ /* Disable all further TX buffer 1 interrupts */
+
+ regval = can_getreg(priv, LPC17_CAN_IER_OFFSET);
+ regval &= ~CAN_IER_TIE1;
+ can_putreg(priv, LPC17_CAN_IER_OFFSET, regval);
+
+ /* Indicate that the TX is done and a new TX buffer is available */
- if ((regval & (CAN_ICR_TI1 | CAN_ICR_TI2 |CAN_ICR_TI3)) != 0)
+ can_txdone(dev);
+ }
+
+ /* Check for TX buffer 2 complete */
+
+ if ((regval & CAN_ICR_TI2) != 0)
+ {
+ /* Disable all further TX buffer 2 interrupts */
+
+ regval = can_getreg(priv, LPC17_CAN_IER_OFFSET);
+ regval &= ~CAN_IER_TIE2;
+ can_putreg(priv, LPC17_CAN_IER_OFFSET, regval);
+
+ /* Indicate that the TX is done and a new TX buffer is available */
+
+ can_txdone(dev);
+ }
+
+ /* Check for TX buffer 3 complete */
+
+ if ((regval & CAN_ICR_TI3) != 0)
{
- /* Disable all further TX interrupts */
+ /* Disable all further TX buffer 3 interrupts */
regval = can_getreg(priv, LPC17_CAN_IER_OFFSET);
- regval &= ~(CAN_IER_TIE1 | CAN_IER_TIE2 | CAN_IER_TIE3);
+ regval &= ~CAN_IER_TIE3;
can_putreg(priv, LPC17_CAN_IER_OFFSET, regval);
/* Indicate that the TX is done and a new TX buffer is available */
diff --git a/nuttx/configs/stm3240g-eval/nsh/defconfig b/nuttx/configs/stm3240g-eval/nsh/defconfig
index f71548b5f..daee8cb72 100755
--- a/nuttx/configs/stm3240g-eval/nsh/defconfig
+++ b/nuttx/configs/stm3240g-eval/nsh/defconfig
@@ -349,13 +349,13 @@ CONFIG_STM32_ADC3_SAMPLE_FREQUENCY=100
# PWM configuration
#
# The STM3240G-Eval has no real on-board PWM devices, but the board can be configured to output
-# a pulse train using several options (see board.h). Here the default setup is for TIM1, CH1.
-# Don't forget to enable CONFIG_STM32_TIM1
+# a pulse train using several options (see board.h). Here the default setup is for TIM4, CH2.
+# Don't forget to enable CONFIG_STM32_TIM4
#
CONFIG_PWM=n
-CONFIG_PWM_PULSECOUNT=y
-CONFIG_STM32_TIM1_PWM=y
-CONFIG_STM32_TIM1_CHANNEL=1
+CONFIG_PWM_PULSECOUNT=n
+CONFIG_STM32_TIM4_PWM=y
+CONFIG_STM32_TIM4_CHANNEL=2
#
# General build options
diff --git a/nuttx/drivers/can.c b/nuttx/drivers/can.c
index 40c179e1c..6928fbd1f 100644
--- a/nuttx/drivers/can.c
+++ b/nuttx/drivers/can.c
@@ -375,9 +375,11 @@ static int can_xmit(FAR struct can_dev_s *dev)
canllvdbg("xmit head: %d tail: %d\n", dev->cd_xmit.cf_head, dev->cd_xmit.cf_tail);
- /* Check if the xmit FIFO is empty */
+ /* Check if the xmit FIFO is not empty and the CAN hardware is ready to accept
+ * more data.
+ */
- if (dev->cd_xmit.cf_head != dev->cd_xmit.cf_tail)
+ if (dev->cd_xmit.cf_head != dev->cd_xmit.cf_tail && dev_txready(dev))
{
/* Send the next message at the head of the FIFO */
@@ -401,7 +403,7 @@ static ssize_t can_write(FAR struct file *filep, FAR const char *buffer, size_t
FAR struct can_dev_s *dev = inode->i_private;
FAR struct can_fifo_s *fifo = &dev->cd_xmit;
FAR struct can_msg_s *msg;
- bool empty = false;
+ bool inactive;
ssize_t nsent = 0;
irqstate_t flags;
int nexttail;
@@ -414,11 +416,12 @@ static ssize_t can_write(FAR struct file *filep, FAR const char *buffer, size_t
flags = irqsave();
- /* Check if the TX FIFO was empty when we started. That is a clue that we have
- * to kick off a new TX sequence.
+ /* Check if the TX is inactive when we started. In certain race conditionas, there
+ * may be a pending interrupt to kick things back off, but we will here that there
+ * is not. That the hardware is IDLE and will need to be kick-started.
*/
- empty = (fifo->cf_head == fifo->cf_tail);
+ inactive = dev_txempty(dev);
/* Add the messages to the FIFO. Ignore any trailing messages that are
* shorter than the minimum.
@@ -455,11 +458,12 @@ static ssize_t can_write(FAR struct file *filep, FAR const char *buffer, size_t
goto return_with_irqdisabled;
}
- /* If the FIFO was empty when we started, then we will have
- * start the XMIT sequence to clear the FIFO.
+ /* If the TX hardware was inactive when we started, then we will have
+ * start the XMIT sequence generate the TX done interrrupts needed
+ * to clear the FIFO.
*/
- if (empty)
+ if (inactive)
{
can_xmit(dev);
}
@@ -483,7 +487,7 @@ static ssize_t can_write(FAR struct file *filep, FAR const char *buffer, size_t
/* Re-check the FIFO state */
- empty = (fifo->cf_head == fifo->cf_tail);
+ inactive = dev_txempty(dev);
}
/* We get here if there is space at the end of the FIFO. Add the new
@@ -507,7 +511,7 @@ static ssize_t can_write(FAR struct file *filep, FAR const char *buffer, size_t
* we need to kick of the XMIT sequence.
*/
- if (empty)
+ if (inactive)
{
can_xmit(dev);
}
diff --git a/nuttx/include/nuttx/can.h b/nuttx/include/nuttx/can.h
index 3f77afc7a..ba060cf5e 100644
--- a/nuttx/include/nuttx/can.h
+++ b/nuttx/include/nuttx/can.h
@@ -1,7 +1,7 @@
/************************************************************************************
* include/nuttx/can.h
*
- * Copyright (C) 2008, 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008, 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
@@ -84,6 +84,7 @@
#define dev_ioctl(dev,cmd,arg) dev->cd_ops->co_ioctl(dev,cmd,arg)
#define dev_remoterequest(dev,id) dev->cd_ops->co_remoterequest(dev,id)
#define dev_send(dev,m) dev->cd_ops->co_send(dev,m)
+#define dev_txready(dev) dev->cd_ops->co_txready(dev)
#define dev_txempty(dev) dev->cd_ops->co_txempty(dev)
/* CAN message support */
@@ -205,6 +206,10 @@ struct can_ops_s
CODE int (*co_send)(FAR struct can_dev_s *dev, FAR struct can_msg_s *msg);
+ /* Return true if the CAN hardware can accept another TX message. */
+
+ CODE bool (*co_txready)(FAR struct can_dev_s *dev);
+
/* Return true if all message have been sent. If for example, the CAN
* hardware implements FIFOs, then this would mean the transmit FIFO is
* empty. This method is called when the driver needs to make sure that