diff --git a/arch/arm/src/samv7/Kconfig b/arch/arm/src/samv7/Kconfig
index 604aa91cec..a467b47849 100644
--- a/arch/arm/src/samv7/Kconfig
+++ b/arch/arm/src/samv7/Kconfig
@@ -3003,4 +3003,51 @@ config SAMV7_MCAN_REGDEBUG
 
 endmenu # CAN device driver options
 endif # SAMV7_MCAN
+
+menu "QEncoder Driver"
+	depends on SENSORS_QENCODER
+	depends on SAMV7_HAVE_TC
+
+config SAMV7_TC0_QE
+	bool "TC0"
+	default n
+	depends on SAMV7_TC0
+	select SAMV7_TC0_TIOA0
+	select SAMV7_TC0_TIOB0
+	---help---
+		Reserve TC0 for use by QEncoder.
+
+config SAMV7_TC1_QE
+	bool "TC1"
+	default n
+	depends on SAMV7_TC1
+	select SAMV7_TC1_TIOA3
+	select SAMV7_TC1_TIOB3
+	---help---
+		Reserve TC1 for use by QEncoder.
+
+config SAMV7_TC2_QE
+	bool "TC2"
+	default n
+	depends on SAMV7_TC2
+	select SAMV7_TC2_TIOA6
+	select SAMV7_TC2_TIOB6
+	---help---
+		Reserve TC2 for use by QEncoder.
+
+config SAMV7_TC3_QE
+	bool "TC3"
+	default n
+	depends on SAMV7_TC3
+	select SAMV7_TC3_TIOA9
+	select SAMV7_TC3_TIOB9
+	---help---
+		Reserve TC3 for use by QEncoder.
+
+config SAMV7_QENCODER_FILTER
+	bool "Enable filtering on SAMV7 QEncoder input"
+	default y
+
+endmenu
+
 endif # ARCH_CHIP_SAMV7
diff --git a/arch/arm/src/samv7/Make.defs b/arch/arm/src/samv7/Make.defs
index 64d0764b2e..88be97306c 100644
--- a/arch/arm/src/samv7/Make.defs
+++ b/arch/arm/src/samv7/Make.defs
@@ -152,6 +152,9 @@ endif
 ifeq ($(CONFIG_SCHED_TICKLESS),y)
 CHIP_CSRCS += sam_tickless.c
 endif
+ifeq ($(CONFIG_SENSORS_QENCODER),y)
+CHIP_CSRCS += sam_qencoder.c
+endif
 endif
 
 ifeq ($(CONFIG_SAMV7_HSMCI),y)
diff --git a/arch/arm/src/samv7/hardware/sam_tc.h b/arch/arm/src/samv7/hardware/sam_tc.h
index ef07b5e496..687e066708 100644
--- a/arch/arm/src/samv7/hardware/sam_tc.h
+++ b/arch/arm/src/samv7/hardware/sam_tc.h
@@ -621,6 +621,7 @@
 #define TC_BMR_INVIDX            (1 << 15) /* Bit 15: INVerted InDeX */
 #define TC_BMR_SWAP              (1 << 16) /* Bit 16: SWAP PHA and PHB */
 #define TC_BMR_IDXPHB            (1 << 17) /* Bit 17: InDeX pin is PHB pin */
+#define TC_BMR_AUTOC             (1 << 18) /* Bit 18: AUTO Correction of missing pulses */
 #define TC_BMR_MAXFILT_SHIFT     (20)      /* Bits 20-25: MAXimum FILTer */
 #define TC_BMR_MAXFILT_MASK      (63 << TC_BMR_MAXFILT_SHIFT)
 #  define TC_BMR_MAXFILT(n)      ((uint32_t)(n) << TC_BMR_MAXFILT_SHIFT)
@@ -630,10 +631,12 @@
  */
 
 #define TC_QINT_IDX              (1 << 0)  /* Bit 0:  Index */
-#define TC_QINT_DIRCHG           (1 << 1)  /* Bit 1:  Direction change */
+#define TC_QINT_DIRCHG           (1 << 1)  /* Bit 1:  DIRection CHanGe */
 #define TC_QINT_QERR             (1 << 2)  /* Bit 2:  Quadrature ERRor */
+#define TC_QINT_MPE              (1 << 3)  /* Bit 3:  Consecutive Missing Pulse Error */
+#define TC_QINT_ALL              (0xf)
 
-#define TC_QISR_DIR              (1 << 8)  /* Bit 8:  Direction */
+#define TC_QISR_DIR              (1 << 8)  /* Bit 8:  DIRection */
 
 /* Fault Mode Register */
 
diff --git a/arch/arm/src/samv7/sam_oneshot.c b/arch/arm/src/samv7/sam_oneshot.c
index c87dc953da..5190387c85 100644
--- a/arch/arm/src/samv7/sam_oneshot.c
+++ b/arch/arm/src/samv7/sam_oneshot.c
@@ -327,7 +327,7 @@ int sam_oneshot_start(struct sam_oneshot_s *oneshot,
    * up to RC.
    */
 
-  sam_tc_setregister(oneshot->tch, TC_REGC, (uint32_t)regval);
+  sam_tc_setregister(oneshot->tch, TC_REGC, regval);
 
   /* Start the counter */
 
@@ -399,8 +399,8 @@ int sam_oneshot_cancel(struct sam_oneshot_s *oneshot,
   uint64_t usec;
   uint64_t sec;
   uint64_t nsec;
-  uint32_t rc;
   uint16_t count;
+  uint16_t rc;
 
   /* Was the timer running? */
 
diff --git a/arch/arm/src/samv7/sam_qencoder.c b/arch/arm/src/samv7/sam_qencoder.c
new file mode 100644
index 0000000000..c685933709
--- /dev/null
+++ b/arch/arm/src/samv7/sam_qencoder.c
@@ -0,0 +1,371 @@
+/****************************************************************************
+ * arch/arm/src/samv7/sam_qencoder.c
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <assert.h>
+#include <errno.h>
+#include <debug.h>
+#include <inttypes.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/irq.h>
+#include <nuttx/sensors/qencoder.h>
+
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "arm_internal.h"
+#include "arm_arch.h"
+
+#include "sam_tc.h"
+#include "sam_qencoder.h"
+
+#ifdef CONFIG_SENSORS_QENCODER
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/* Overall, RAM-based state structure */
+
+struct sam_lowerhalf_s
+{
+  /* The first field of this state structure must be a pointer to the lower-
+   * half callback structure:
+   */
+
+  FAR const struct qe_ops_s *ops;  /* Lower half callback structure */
+
+  /* SAMV7 driver-specific fields: */
+
+  uint8_t          tcid;         /* Timer counter ID {0,1,2,3} */
+  TC_HANDLE        tch;          /* Handle returned by sam_tc_initialize() */
+
+  bool             inuse;        /* True: The lower-half driver is in-use */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/* Helper functions */
+
+static FAR struct sam_lowerhalf_s *sam_tc2lower(int tc);
+
+/* Lower-half Quadrature Encoder Driver Methods */
+
+static int sam_setup(FAR struct qe_lowerhalf_s *lower);
+static int sam_shutdown(FAR struct qe_lowerhalf_s *lower);
+static int sam_position(FAR struct qe_lowerhalf_s *lower, FAR int32_t *pos);
+static int sam_reset(FAR struct qe_lowerhalf_s *lower);
+static int sam_ioctl(FAR struct qe_lowerhalf_s *lower, int cmd,
+                     unsigned long arg);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* The lower half callback structure */
+
+static const struct qe_ops_s g_qecallbacks =
+{
+  .setup     = sam_setup,
+  .shutdown  = sam_shutdown,
+  .position  = sam_position,
+  .setposmax = NULL,            /* not supported yet */
+  .reset     = sam_reset,
+  .setindex  = NULL,            /* not supported yet */
+  .ioctl     = sam_ioctl,
+};
+
+/* Per-timer state structures */
+
+#ifdef CONFIG_SAMV7_TC0_QE
+static struct sam_lowerhalf_s g_tc0lower =
+{
+  .ops      = &g_qecallbacks,
+  .tcid     = 0,
+  .inuse    = false,
+};
+#endif
+
+#ifdef CONFIG_SAMV7_TC1_QE
+static struct sam_lowerhalf_s g_tc1lower =
+{
+  .ops      = &g_qecallbacks,
+  .timid    = 1,
+  .inuse    = false,
+};
+#endif
+
+#ifdef CONFIG_SAMV7_TC2_QE
+static struct sam_lowerhalf_s g_tc2lower =
+{
+  .ops      = &g_qecallbacks,
+  .tcid     = 2,
+  .inuse    = false,
+};
+#endif
+
+#ifdef CONFIG_SAMV7_TC3_QE
+static struct sam_lowerhalf_s g_tc3lower =
+{
+  .ops      = &g_qecallbacks,
+  .tcid     = 3,
+  .inuse    = false,
+};
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_tc2lower
+ *
+ * Description:
+ *   Map a timer counter number to a device structure
+ *
+ ****************************************************************************/
+
+static FAR struct sam_lowerhalf_s *sam_tc2lower(int tc)
+{
+  switch (tc)
+    {
+#ifdef CONFIG_SAMV7_TC0_QE
+    case 0:
+      return &g_tc0lower;
+#endif
+#ifdef CONFIG_SAMV7_TC1_QE
+    case 1:
+      return &g_tc1lower;
+#endif
+#ifdef CONFIG_SAMV7_TC2_QE
+    case 2:
+      return &g_tc2lower;
+#endif
+#ifdef CONFIG_SAMV7_TC3_QE
+    case 3:
+      return &g_tc3lower;
+#endif
+    default:
+      return NULL;
+    }
+}
+
+/****************************************************************************
+ * Name: sam_setup
+ *
+ * Description:
+ *   This method is called when the driver is opened.  The lower half driver
+ *   should configure and initialize the device so that it is ready for use.
+ *   The initial position value should be zero.
+ *
+ ****************************************************************************/
+
+static int sam_setup(FAR struct qe_lowerhalf_s *lower)
+{
+  FAR struct sam_lowerhalf_s *priv = (FAR struct sam_lowerhalf_s *)lower;
+
+  /* Start the counter */
+
+  sam_tc_start(priv->tch);
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: sam_shutdown
+ *
+ * Description:
+ *   This method is called when the driver is closed.  The lower half driver
+ *   should stop data collection, free any resources, disable timer hardware,
+ *   and put the system into the lowest possible power usage state
+ *
+ ****************************************************************************/
+
+static int sam_shutdown(FAR struct qe_lowerhalf_s *lower)
+{
+  FAR struct sam_lowerhalf_s *priv = (FAR struct sam_lowerhalf_s *)lower;
+
+  sam_tc_stop(priv->tch);
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: sam_position
+ *
+ * Description:
+ *   Return the current position measurement.
+ *
+ ****************************************************************************/
+
+static int sam_position(FAR struct qe_lowerhalf_s *lower, FAR int32_t *pos)
+{
+  FAR struct sam_lowerhalf_s *priv = (FAR struct sam_lowerhalf_s *)lower;
+
+  /* Return the counter value */
+
+  *pos = (int32_t)sam_tc_getcounter(priv->tch);
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: sam_reset
+ *
+ * Description:
+ *   Reset the position measurement to zero.
+ *
+ ****************************************************************************/
+
+static int sam_reset(FAR struct qe_lowerhalf_s *lower)
+{
+  FAR struct sam_lowerhalf_s *priv = (FAR struct sam_lowerhalf_s *)lower;
+
+  sninfo("Resetting position to zero\n");
+  DEBUGASSERT(lower && priv->inuse);
+
+  sam_tc_stop(priv->tch);
+
+  sam_tc_start(priv->tch);
+
+  return OK;
+}
+
+/****************************************************************************
+ * Name: sam_ioctl
+ *
+ * Description:
+ *   Lower-half logic may support platform-specific ioctl commands
+ *
+ ****************************************************************************/
+
+static int sam_ioctl(FAR struct qe_lowerhalf_s *lower, int cmd,
+                     unsigned long arg)
+{
+  /* No ioctl commands supported */
+
+  return -ENOTTY;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_qeinitialize
+ *
+ * Description:
+ *   Initialize a quadrature encoder interface.  This function must be
+ *   called from board-specific logic.
+ *
+ * Input Parameters:
+ *   devpath - The full path to the driver to register. E.g., "/dev/qe0"
+ *   tc      - The timer counter number to used.  'tc' must be an element of
+ *             {0,1,2,3}
+ *
+ * Returned Value:
+ *   Zero on success; A negated errno value is returned on failure.
+ *
+ ****************************************************************************/
+
+int sam_qeinitialize(FAR const char *devpath, int tc)
+{
+  FAR struct sam_lowerhalf_s *priv;
+  uint32_t mode;
+  int ret;
+
+  /* Find the pre-allocated timer state structure corresponding to this
+   * timer
+   */
+
+  priv = sam_tc2lower(tc);
+  if (!priv)
+    {
+      snerr("ERROR: TC%d support not configured\n", tc);
+      return -ENXIO;
+    }
+
+  /* Make sure that it is available */
+
+  if (priv->inuse)
+    {
+      snerr("ERROR: TC%d is in-use\n", tc);
+      return -EBUSY;
+    }
+
+  /* Allocate the timer/counter and select its mode of operation */
+
+  mode = TC_CMR_TCCLKS_XC0 |     /* Use XC0 as an external TCCLKS value */
+         TC_CMR_ETRGEDG_RISING | /* Select ‘Rising edge’ as the External Trigger Edge */
+         TC_CMR_ABETRG |         /* Select ‘TIOAx’ as the External Trigger */
+         TC_CMR_CAPTURE;         /* Select 'Capture mode' */
+
+  priv->tch = sam_tc_allocate(tc * SAM_TC_NCHANNELS, mode);
+  if (priv->tch == NULL)
+    {
+      tmrerr("ERROR: Failed to allocate timer channel %d\n",
+             tc * SAM_TC_NCHANNELS);
+      return -EBUSY;
+    }
+
+  /* Define timer block mode */
+
+  mode = TC_BMR_QDEN |      /* Enable Quadrature Decoder */
+         TC_BMR_POSEN |     /* Enable Position Measurement on timer channel */
+         TC_BMR_EDGPHA |    /* Select Edge Detection Mode */
+         TC_BMR_AUTOC |     /* Enable Auto-Correction of Missing Pulses */
+#ifdef CONFIG_SAMV7_QENCODER_FILTER
+         TC_BMR_MAXFILT(1); /* Define Filtering Capabilities */
+#else
+         TC_BMR_MAXFILT(0); /* Disable Filtering Capabilities */
+#endif
+
+  sam_tc_setblockmode(priv->tch, mode);
+
+  /* Register the upper-half driver */
+
+  ret = qe_register(devpath, (FAR struct qe_lowerhalf_s *)priv);
+  if (ret < 0)
+    {
+      snerr("ERROR: qe_register failed: %d\n", ret);
+      sam_tc_free(priv->tch);
+      return ret;
+    }
+
+  /* The driver is now in-use */
+
+  priv->inuse = true;
+  return OK;
+}
+
+#endif /* CONFIG_SENSORS_QENCODER */
diff --git a/arch/arm/src/samv7/sam_qencoder.h b/arch/arm/src/samv7/sam_qencoder.h
new file mode 100644
index 0000000000..883dbbbf33
--- /dev/null
+++ b/arch/arm/src/samv7/sam_qencoder.h
@@ -0,0 +1,81 @@
+/****************************************************************************
+ * arch/arm/src/samv7/sam_qencoder.h
+ *
+ * Licensed to the Apache Software Foundation (ASF) under one or more
+ * contributor license agreements.  See the NOTICE file distributed with
+ * this work for additional information regarding copyright ownership.  The
+ * ASF licenses this file to you under the Apache License, Version 2.0 (the
+ * "License"); you may not use this file except in compliance with the
+ * License.  You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
+ * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.  See the
+ * License for the specific language governing permissions and limitations
+ * under the License.
+ *
+ ****************************************************************************/
+
+#ifndef __ARCH_ARM_SRC_SAMV7_SAM_QENCODER_H
+#define __ARCH_ARM_SRC_SAMV7_SAM_QENCODER_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include "chip.h"
+
+#ifdef CONFIG_SENSORS_QENCODER
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/* Timer devices may be used for different purposes.  One special purpose is
+ * as a quadrature encoder input device.  CONFIG_SAMV7_TCn is defined
+ * then the CONFIG_SAMV7_TCn_QE must also be defined to indicate that timer
+ * "n" is intended to be used for as a quadrature encoder.
+ */
+
+#ifndef CONFIG_SAMV7_TC0
+#  undef CONFIG_SAMV7_TC0_QE
+#endif
+#ifndef CONFIG_SAMV7_TC1
+#  undef CONFIG_SAMV7_TC1_QE
+#endif
+#ifndef CONFIG_SAMV7_TC2
+#  undef CONFIG_SAMV7_TC2_QE
+#endif
+#ifndef CONFIG_SAMV7_TC3
+#  undef CONFIG_SAMV7_TC3_QE
+#endif
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: sam_qeinitialize
+ *
+ * Description:
+ *   Initialize a quadrature encoder interface.  This function must be called
+ *   from board-specific logic..
+ *
+ * Input Parameters:
+ *   devpath - The full path to the driver to register. E.g., "/dev/qe0"
+ *   tc      - The timer counter number to used.  'tc' must be an element of
+ *             {0,1,2,3}
+ *
+ * Returned Value:
+ *   Zero on success; A negated errno value is returned on failure.
+ *
+ ****************************************************************************/
+
+int sam_qeinitialize(FAR const char *devpath, int tc);
+
+#endif /* CONFIG_SENSORS_QENCODER */
+#endif /* __ARCH_ARM_SRC_SAMV7_SAM_QENCODER_H */
diff --git a/arch/arm/src/samv7/sam_tc.c b/arch/arm/src/samv7/sam_tc.c
index a8c03e1c37..d54e70c6d5 100644
--- a/arch/arm/src/samv7/sam_tc.c
+++ b/arch/arm/src/samv7/sam_tc.c
@@ -175,7 +175,7 @@ static bool sam_checkreg(struct sam_tc_s *tc, bool wr, uint32_t regaddr,
 static inline uint32_t sam_tc_getreg(struct sam_chan_s *chan,
                                      unsigned int offset);
 static inline void sam_tc_putreg(struct sam_chan_s *chan,
-                                 uint32_t regval, unsigned int offset);
+                                 unsigned int offset, uint32_t regval);
 
 static inline uint32_t sam_chan_getreg(struct sam_chan_s *chan,
                                        unsigned int offset);
@@ -729,8 +729,8 @@ static inline uint32_t sam_tc_getreg(struct sam_chan_s *chan,
  *
  ****************************************************************************/
 
-static inline void sam_tc_putreg(struct sam_chan_s *chan, uint32_t regval,
-                                 unsigned int offset)
+static inline void sam_tc_putreg(struct sam_chan_s *chan,
+                                 unsigned int offset, uint32_t regval)
 {
   struct sam_tc_s *tc = chan->tc;
   uint32_t regaddr    = tc->base + offset;
@@ -825,8 +825,8 @@ static int sam_tc_interrupt(int irq, void *context, FAR void *arg)
   imr     = sam_chan_getreg(chan, SAM_TC_IMR_OFFSET);
   pending = sr & imr;
 
-  tmrinfo("TC%d Channel %d: pending=%08lx\n",
-          chan->tc->tc, chan->chan, (unsigned long)pending);
+  tmrinfo("TC%u Channel %u: pending=%08" PRIx32 "\n",
+          chan->tc->tc, chan->chan, pending);
 
   /* Are there any pending interrupts for this channel? */
 
@@ -1299,6 +1299,7 @@ void sam_tc_free(TC_HANDLE handle)
  *   handle Channel handle previously allocated by sam_tc_allocate()
  *
  * Returned Value:
+ *   None
  *
  ****************************************************************************/
 
@@ -1331,6 +1332,7 @@ void sam_tc_start(TC_HANDLE handle)
  *   handle Channel handle previously allocated by sam_tc_allocate()
  *
  * Returned Value:
+ *   None
  *
  ****************************************************************************/
 
@@ -1359,9 +1361,10 @@ void sam_tc_stop(TC_HANDLE handle)
  *   arg     An opaque argument that will be provided when the interrupt
  *           handler callback is executed.
  *   mask    The value of the timer interrupt mask register that defines
- *           which interrupts should be disabled.
+ *           which interrupts should be enabled.
  *
  * Returned Value:
+ *   The old timer channel interrupt handler
  *
  ****************************************************************************/
 
@@ -1384,7 +1387,7 @@ tc_handler_t sam_tc_attach(TC_HANDLE handle, tc_handler_t handler,
    * says.
    */
 
-  if (!handler)
+  if (handler == NULL)
     {
       arg  = NULL;
       mask = 0;
@@ -1439,14 +1442,14 @@ uint32_t sam_tc_getpending(TC_HANDLE handle)
  *
  ****************************************************************************/
 
-void sam_tc_setregister(TC_HANDLE handle, int regid, uint32_t regval)
+void sam_tc_setregister(TC_HANDLE handle, int regid, uint16_t regval)
 {
   struct sam_chan_s *chan = (struct sam_chan_s *)handle;
 
   DEBUGASSERT(chan && regid < TC_NREGISTERS);
 
-  tmrinfo("Channel %d: Set register RC%d to %08lx\n",
-          chan->chan, regid, (unsigned long)regval);
+  tmrinfo("Channel %u: Set register RC%d to %04x\n",
+          chan->chan, regid, regval);
 
   sam_chan_putreg(chan, g_regoffset[regid], regval);
   sam_regdump(chan, "Set register");
@@ -1467,7 +1470,7 @@ void sam_tc_setregister(TC_HANDLE handle, int regid, uint32_t regval)
  *
  ****************************************************************************/
 
-uint32_t sam_tc_getregister(TC_HANDLE handle, int regid)
+uint16_t sam_tc_getregister(TC_HANDLE handle, int regid)
 {
   struct sam_chan_s *chan = (struct sam_chan_s *)handle;
   DEBUGASSERT(chan);
@@ -1484,7 +1487,7 @@ uint32_t sam_tc_getregister(TC_HANDLE handle, int regid)
  *   handle Channel handle previously allocated by sam_tc_allocate()
  *
  * Returned Value:
- *  The current value of the timer counter register for this channel.
+ *   The current value of the timer counter register for this channel.
  *
  ****************************************************************************/
 
@@ -1495,6 +1498,28 @@ uint16_t sam_tc_getcounter(TC_HANDLE handle)
   return sam_chan_getreg(chan, SAM_TC_CV_OFFSET);
 }
 
+/****************************************************************************
+ * Name: sam_tc_setblockmode
+ *
+ * Description:
+ *   Set the value of TC_BMR register
+ *
+ * Input Parameters:
+ *   handle Channel handle previously allocated by sam_tc_allocate()
+ *   regval Then value to set in the register
+ *
+ * Returned Value:
+ *   None
+ *
+ ****************************************************************************/
+
+void sam_tc_setblockmode(TC_HANDLE handle, uint32_t regval)
+{
+  struct sam_chan_s *chan = (struct sam_chan_s *)handle;
+  DEBUGASSERT(chan);
+  sam_tc_putreg(chan, SAM_TC_BMR_OFFSET, regval);
+}
+
 /****************************************************************************
  * Name: sam_tc_divfreq
  *
@@ -1506,7 +1531,7 @@ uint16_t sam_tc_getcounter(TC_HANDLE handle)
  *   handle Channel handle previously allocated by sam_tc_allocate()
  *
  * Returned Value:
- *  The timer counter frequency.
+ *   The timer counter frequency.
  *
  ****************************************************************************/
 
diff --git a/arch/arm/src/samv7/sam_tc.h b/arch/arm/src/samv7/sam_tc.h
index d77da1c275..1b13d74059 100644
--- a/arch/arm/src/samv7/sam_tc.h
+++ b/arch/arm/src/samv7/sam_tc.h
@@ -189,7 +189,7 @@ void sam_tc_stop(TC_HANDLE handle);
  *   arg     An opaque argument that will be provided when the interrupt
  *           handler callback is executed.  Ignored if handler is NULL.
  *   mask    The value of the timer interrupt mask register that defines
- *           which interrupts should be disabled.  Ignored if handler is
+ *           which interrupts should be enabled.  Ignored if handler is
  *           NULL.
  *
  * Returned Value:
@@ -235,7 +235,7 @@ uint32_t sam_tc_getpending(TC_HANDLE handle);
  *
  ****************************************************************************/
 
-void sam_tc_setregister(TC_HANDLE handle, int regid, uint32_t regval);
+void sam_tc_setregister(TC_HANDLE handle, int regid, uint16_t regval);
 
 /****************************************************************************
  * Name: sam_tc_getregister
@@ -252,7 +252,7 @@ void sam_tc_setregister(TC_HANDLE handle, int regid, uint32_t regval);
  *
  ****************************************************************************/
 
-uint32_t sam_tc_getregister(TC_HANDLE handle, int regid);
+uint16_t sam_tc_getregister(TC_HANDLE handle, int regid);
 
 /****************************************************************************
  * Name: sam_tc_getcounter
@@ -270,6 +270,23 @@ uint32_t sam_tc_getregister(TC_HANDLE handle, int regid);
 
 uint16_t sam_tc_getcounter(TC_HANDLE handle);
 
+/****************************************************************************
+ * Name: sam_tc_setblockmode
+ *
+ * Description:
+ *   Set the value of TC_BMR register
+ *
+ * Input Parameters:
+ *   handle Channel handle previously allocated by sam_tc_allocate()
+ *   regval Then value to set in the register
+ *
+ * Returned Value:
+ *   None
+ *
+ ****************************************************************************/
+
+void sam_tc_setblockmode(TC_HANDLE handle, uint32_t regval);
+
 /****************************************************************************
  * Name: sam_tc_infreq
  *