]> oss.titaniummirror.com Git - tinyos-2.x.git/commitdiff
msp430 usci: TX operations via DMA
authorR. Steve McKown <rsmckown@gmail.com>
Tue, 23 Dec 2014 19:50:45 +0000 (12:50 -0700)
committerR. Steve McKown <rsmckown@gmail.com>
Tue, 23 Dec 2014 19:50:45 +0000 (12:50 -0700)
USCI UART A0 and A1 support DMA transmit via Msp430UartDmaA0C and
Msp430UartDmaA1C, respectively.  Since both components are implemented
using DMA channel 0, they cannot be both utilized in the same program.

A future parameterized DMA interface could be used to allow
serialization of DMA operations between UARTs using a single DMA
channel.

tos/chips/msp430/usci/Msp430UartDmaA0C.nc [new file with mode: 0644]
tos/chips/msp430/usci/Msp430UartDmaA1C.nc [new file with mode: 0644]
tos/chips/msp430/usci/Msp430UartDmaP.nc [new file with mode: 0644]

diff --git a/tos/chips/msp430/usci/Msp430UartDmaA0C.nc b/tos/chips/msp430/usci/Msp430UartDmaA0C.nc
new file mode 100644 (file)
index 0000000..ba45f87
--- /dev/null
@@ -0,0 +1,78 @@
+/*
+ * Copyright (c) 2008, Titanium Mirror, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * - Redistributions of source code must retain the above copyright notice,
+ *   this list of conditions and the following disclaimer.
+ * - Redistributions in binary form must reproduce the above copyright
+ *   notice, this list of conditions and the following disclaimer in the
+ *   documentation and/or other materials provided with the distribution.
+ * - Neither the name of the Titanium Mirror, Inc. nor the names
+ *   of its contributors may be used to endorse or promote products derived
+ *   from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
+ * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
+ * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
+ * OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE
+ * USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/**
+ * This configuration provides the interface for using USCI_A0 in its UART
+ * mode.
+ *
+ * @author R. Steve McKown <rsmckown@gmail.com>
+ */
+
+#if !defined(__MSP430_HAS_USCI_AB0__)
+#error "Target does not have a USCI_A0 peripheral (UART)"
+#endif
+
+#include "Msp430Usci.h"
+
+generic configuration Msp430UartA0C() {
+  provides {
+    interface Resource;
+    interface ResourceRequested;
+    interface UartStream;
+    interface UartByte;
+    interface ArbiterInfo; /* ??? */
+  }
+  uses interface AsyncConfigure<const msp430_usci_uart_t*> as Configure;
+}
+implementation {
+  enum {
+    CLIENT_ID = unique(MSP430_USCIA0_RESOURCE)
+  };
+
+  components new Msp430UartDmaP(UCA0TXBUF_, DMA0TSEL_4) as UartP;
+  UartStream = UartP;
+  UartByte = UartP;
+  Configure = UartP;
+
+  components Msp430UsciA0C as UsciC;
+  Resource = UsciC.Resource[CLIENT_ID];
+  ResourceRequested = UsciC.ResourceRequested[CLIENT_ID];
+  ArbiterInfo = UsciC.ArbiterInfo;
+  UartP -> UsciC.Registers;
+  UartP -> UsciC.Interrupts[CLIENT_ID];
+  UartP -> UsciC.ArbiterInfo;
+  UsciC.ResourceConfigure[CLIENT_ID] -> UartP;
+
+  components HplMsp430GeneralIOC as IOC;
+  UartP.RXD -> IOC.UCA0RXD;
+  UartP.TXD -> IOC.UCA0TXD;
+
+  components Msp430DmaC as DmaC;
+  UartP.DmaChannel -> DmaC.Channel0;
+}
diff --git a/tos/chips/msp430/usci/Msp430UartDmaA1C.nc b/tos/chips/msp430/usci/Msp430UartDmaA1C.nc
new file mode 100644 (file)
index 0000000..8567d47
--- /dev/null
@@ -0,0 +1,78 @@
+/*
+ * Copyright (c) 2008, Titanium Mirror, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * - Redistributions of source code must retain the above copyright notice,
+ *   this list of conditions and the following disclaimer.
+ * - Redistributions in binary form must reproduce the above copyright
+ *   notice, this list of conditions and the following disclaimer in the
+ *   documentation and/or other materials provided with the distribution.
+ * - Neither the name of the Titanium Mirror, Inc. nor the names
+ *   of its contributors may be used to endorse or promote products derived
+ *   from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
+ * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
+ * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
+ * OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE
+ * USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/**
+ * This configuration provides the interface for using USCI_A1 in its UART
+ * mode.
+ *
+ * @author R. Steve McKown <rsmckown@gmail.com>
+ */
+
+#if !defined(__MSP430_HAS_USCI_AB0__)
+#error "Target does not have a USCI_A1 peripheral (UART)"
+#endif
+
+#include "Msp430Usci.h"
+
+generic configuration Msp430UartDmaA1C() {
+  provides {
+    interface Resource;
+    interface ResourceRequested;
+    interface UartStream;
+    interface UartByte;
+    interface ArbiterInfo; /* ??? */
+  }
+  uses interface AsyncConfigure<const msp430_usci_uart_t*> as Configure;
+}
+implementation {
+  enum {
+    CLIENT_ID = unique(MSP430_USCIA1_RESOURCE)
+  };
+
+  components new Msp430UartDmaP(UCA1TXBUF_, DMA0TSEL_10) as UartP;
+  UartStream = UartP;
+  UartByte = UartP;
+  Configure = UartP;
+
+  components Msp430UsciA1C as UsciC;
+  Resource = UsciC.Resource[CLIENT_ID];
+  ResourceRequested = UsciC.ResourceRequested[CLIENT_ID];
+  ArbiterInfo = UsciC.ArbiterInfo;
+  UartP -> UsciC.Registers;
+  UartP -> UsciC.Interrupts[CLIENT_ID];
+  UartP -> UsciC.ArbiterInfo;
+  UsciC.ResourceConfigure[CLIENT_ID] -> UartP;
+
+  components HplMsp430GeneralIOC as IOC;
+  UartP.RXD -> IOC.UCA1RXD;
+  UartP.TXD -> IOC.UCA1TXD;
+
+  components Msp430DmaC as DmaC;
+  UartP.DmaChannel -> DmaC.Channel0;
+}
diff --git a/tos/chips/msp430/usci/Msp430UartDmaP.nc b/tos/chips/msp430/usci/Msp430UartDmaP.nc
new file mode 100644 (file)
index 0000000..99a5c91
--- /dev/null
@@ -0,0 +1,299 @@
+/*
+ * Copyright (c) 2008, Titanium Mirror, Inc.
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * - Redistributions of source code must retain the above copyright notice,
+ *   this list of conditions and the following disclaimer.
+ * - Redistributions in binary form must reproduce the above copyright
+ *   notice, this list of conditions and the following disclaimer in the
+ *   documentation and/or other materials provided with the distribution.
+ * - Neither the name of the Titanium Mirror, Inc. nor the names
+ *   of its contributors may be used to endorse or promote products derived
+ *   from this software without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+ * A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+ * OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
+ * TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
+ * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY
+ * OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE
+ * USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+/**
+ * Uart implementation using a USCI device.
+ *
+ * TODO: Implement blocking like in Msp430UartSpiP.nc.
+ *       Implement error checking via UCAxSTAT.
+ *
+ * @author R. Steve McKown <rsmckown@gmail.com>
+ */
+
+#include "msp430hardware.h" /* SET_FLAG() */
+
+generic module Msp430UartDmaP(uint16_t UCxxTXBUF_, uint16_t DMAxTSEL_x) {
+  provides {
+    interface UartStream;
+    interface UartByte;
+    interface ResourceConfigure;
+  }
+  uses {
+    interface HplMsp430UsciReg as Registers;
+    interface HplMsp430UsciInt as Interrupts;
+    interface HplMsp430GeneralIO as RXD;
+    interface HplMsp430GeneralIO as TXD;
+    interface Msp430DmaChannel as DmaChannel;
+    interface AsyncConfigure<const msp430_usci_uart_t*> as Configure;
+    interface ArbiterInfo;
+  }
+}
+implementation {
+  enum {
+    /* Bit positions in m_pins */
+    PINS_RXD = 0,
+    PINS_TXD
+  };
+
+  uint8_t m_pins;
+  uint8_t* m_sobuf;    /* Original buffer ptr from UartStream.send() */
+  uint16_t m_solen;    /* Original buffer len from UartStream.send() */
+  bool m_rxie;         /* Set if rxie has been enabled to UartStream.receive() */
+  uint8_t* m_robuf;    /* Original receive buffer */
+  uint16_t m_rolen;    /* Original (maximum) receive len */
+  uint8_t* m_rbuf;     /* Position of next byte in which to receive a char */
+  uint16_t m_rlen;     /* Remaining length in receive buffer */
+
+  sfrb(MYBRX, 219U);
+
+  async command void ResourceConfigure.configure()
+  {
+    atomic {
+      const msp430_usci_uart_t* config = call Configure.get();
+
+      call Registers.setCtl1(UCSWRST);
+
+      /* Configure USCI registers */
+      call Registers.assignCtl0(config->ctl0 & ~UCSYNC);
+      call Registers.assignCtl1(config->ctl1 | UCSWRST);
+      call Registers.assignBr0(config->brx & 0xff);
+      call Registers.assignBr1(config->brx >> 8);
+      call Registers.assignMctl(config->mctl);
+      call Registers.assignIrtctl(config->irtctl);
+      call Registers.assignIrrctl(config->irrctl);
+      call Registers.assignAbctl(config->abctl);
+      if (config->uclisten)
+       call Registers.setStat(UCLISTEN);
+      else
+       call Registers.clrStat(UCLISTEN);
+
+      /* Configure pins for UART, saving prior pin states */
+      m_pins = 0;
+      if (call RXD.isIOFunc()) {
+       m_pins |= (1 << PINS_RXD);
+       call RXD.selectModuleFunc();
+      }
+      if (call TXD.isIOFunc()) {
+       m_pins |= (1 << PINS_TXD);
+       call TXD.selectModuleFunc();
+      }
+
+      /* Reset important state variables */
+      m_robuf = 0;
+      m_sobuf = 0;
+
+      /* Clear interrupts; we'll add them as needed */
+      call Registers.clrIeRx();
+      call Registers.clrIeTx();
+
+      /* Enable the device */
+      call Registers.clrCtl1(UCSWRST);
+
+      /* TOS convention is for receive interrupts on by default. */
+      call Registers.clrIfgRx();
+      call Registers.setIeRx();
+    }
+  }
+
+  async command void ResourceConfigure.unconfigure()
+  {
+    atomic {
+      /* Disable the device */
+      call Registers.setCtl1(UCSWRST);
+
+      /* Clear interrupts and interrupt flags */
+      call Registers.clrIeRx();
+      call Registers.clrIeTx();
+      call Registers.clrIfgRx();
+
+      /* Reset important state variables */
+      m_robuf = 0;
+      m_sobuf = 0;
+
+      /* Restore pins to their pre-configure state */
+      if (m_pins & (1 << PINS_RXD))
+       call RXD.selectIOFunc();
+      if (m_pins & (1 << PINS_TXD))
+       call TXD.selectIOFunc();
+    }
+  }
+
+  async command error_t UartByte.send(uint8_t byte)
+  {
+    atomic {
+      while (!call Registers.getIfgTx());
+      call Registers.setTxbuf(byte);
+      return SUCCESS;
+    }
+  }
+
+  async command error_t UartStream.send(uint8_t* buf, uint16_t len)
+  {
+    atomic {
+      if (m_sobuf || !buf || !len)
+       return FAIL;
+      m_sobuf = buf;
+      m_solen = len;
+    }
+
+    call Registers.clrIfgTx();
+
+    /* Configure DMA to transfer m_solen bytes from m_sobuf */
+    call DmaChannel.setupTransfer(DMA_SINGLE_TRANSFER, DMAxTSEL_x,
+        DMA_EDGE_SENSITIVE, m_sobuf, (void *)UCxxTXBUF_, m_solen, DMA_BYTE,
+        DMA_BYTE, DMA_ADDRESS_INCREMENTED, DMA_ADDRESS_UNCHANGED);
+    call DmaChannel.startTransfer();
+
+    /* Set IFGTX to start DMA transfers */
+    call Registers.setIfgTx();
+    return SUCCESS;
+  }
+
+  async event void DmaChannel.transferDone(error_t error)
+  {
+    if (m_sobuf) {
+      m_sobuf = 0;
+      signal UartStream.sendDone(m_sobuf, m_solen, error);
+    }
+  }
+
+  async event void Interrupts.tx() {}
+
+  async command error_t UartStream.enableReceiveInterrupt()
+  {
+    atomic {
+      if (!m_robuf)
+       call Registers.clrIfgRx();
+      call Registers.setIeRx();
+      m_rxie = FALSE;
+      return SUCCESS;
+    }
+  }
+
+  async command error_t UartStream.disableReceiveInterrupt()
+  {
+    atomic {
+      if (!m_robuf) {
+       call Registers.clrIeRx();
+       call Registers.clrIfgRx();
+      } else
+       m_rxie = TRUE;
+      return SUCCESS;
+    }
+  }
+
+  async command error_t UartByte.receive(uint8_t* byte, uint8_t timeout)
+  {
+    atomic {
+      uint16_t t;
+
+      /* FIXME: race with UartStream.receive() */
+      if (m_robuf || !byte)
+       return FAIL;
+      /* TODO: implement timeout, byte-time units.  For now, 1-2 sec */
+      t = TBR;
+      while (t < TBR) {
+       if (call Registers.getIfgRx()) {
+         *byte = call Registers.getRxbuf();
+         return SUCCESS;
+       }
+      }
+      return FAIL;
+    }
+  }
+
+  async command error_t UartStream.receive(uint8_t* buf, uint16_t len)
+  {
+    atomic {
+      if (m_robuf || !buf || !len)
+       return FAIL;
+      m_robuf = m_rbuf = buf;
+      m_rolen = m_rlen = len;
+      if (!call Registers.getIeRx()) {
+       call Registers.clrIfgRx();
+       call Registers.setIeRx();
+       m_rxie = TRUE;
+      } else
+       m_rxie = FALSE;
+    }
+  }
+
+  async event void Interrupts.rx(uint8_t byte)
+  {
+    if (m_robuf) {
+      /* receive() takes precedence if active */
+      /* FIXME: an arbitrarily long ISR may occur if m_rlen is large.
+       * But depending on timing, we may always only read 1 byte.
+       */
+      while (m_rlen && call Registers.getIfgRx()) {
+       *m_rbuf = byte;
+       if (--m_rlen)
+         m_rbuf++;
+      }
+      if (m_rlen == 0 && m_robuf) {
+       if (m_rxie) {
+         call Registers.clrIeRx();
+         call Registers.clrIfgRx();
+       }
+       m_robuf = 0;
+       signal UartStream.receiveDone(m_robuf, m_rolen, SUCCESS);
+      }
+    } else
+      signal UartStream.receivedByte(byte);
+  }
+
+  default async command const msp430_usci_uart_t* Configure.get()
+  {
+    const static msp430_usci_uart_t def = {
+      ctl0: UCMODE_0,          /* async, lsb first, 8N1 */
+      ctl1: UCSWRST | UCSSEL_3,        /* clock uart from SMCLK */
+      brx: UBRX_1MHZ_115200,
+      mctl: UMCTL_1MHZ_115200,
+      irtctl: 0,
+      irrctl: 0,
+      abctl: 0,
+      uclisten: FALSE,
+      ren: USCI_REN_NONE
+    };
+
+    return &def;
+  }
+
+  async event void Interrupts.i2cStart() {}
+  async event void Interrupts.i2cStop() {}
+  async event void Interrupts.i2cCal() {}
+  async event void Interrupts.brk() {}
+  async event void Interrupts.i2cNack() {}
+
+  default async event void UartStream.sendDone( uint8_t* buf, uint16_t len,
+      error_t error ) {}
+  default async event void UartStream.receivedByte( uint8_t byte ) {}
+  default async event void UartStream.receiveDone( uint8_t* buf, uint16_t len,
+      error_t error ) {}
+}