From d99aaff2fbe4bea541428c600fc68af33846ebdc Mon Sep 17 00:00:00 2001
From: Hauke Petersen <hauke.petersen@fu-berlin.de>
Date: Fri, 4 Sep 2015 18:45:32 +0200
Subject: [PATCH] drivers/srf02: various optimizations

- switched to use xtimer
- simplified interface slightly
- optimized reading of results
- some style cleanups
- updated the documentation
---
 Makefile.dep            |   4 ++
 drivers/include/srf02.h |  64 ++++++++++---------------
 drivers/srf02/srf02.c   | 101 +++++++++++++++++++++-------------------
 3 files changed, 81 insertions(+), 88 deletions(-)

diff --git a/Makefile.dep b/Makefile.dep
index 5ba1a10e5d..e5239c3a49 100644
--- a/Makefile.dep
+++ b/Makefile.dep
@@ -279,3 +279,7 @@ ifneq (,$(filter encx24j600,$(USEMODULE)))
   USEMODULE += timex
   USEMODULE += vtimer
 endif
+
+ifneq (,$(filter srf02,$(USEMODULE)))
+  USEMODULE += xtimer
+endif
diff --git a/drivers/include/srf02.h b/drivers/include/srf02.h
index d47245bc5f..c7065aaa2e 100644
--- a/drivers/include/srf02.h
+++ b/drivers/include/srf02.h
@@ -1,5 +1,6 @@
 /*
  * Copyright (C) 2013 Zakaria Kasmi <zkasmi@inf.fu-berlin.de>
+ *               2015 Freie Universität Berlin
  *
  * This file is subject to the terms and conditions of the GNU Lesser General
  * Public License v2.1. See the file LICENSE in the top level directory for more
@@ -7,27 +8,22 @@
  */
 
 /**
- * @defgroup    driver_srf02 SRF02 ultrasonic range sensor
+ * @defgroup    driver_srf02 SRF02
  * @ingroup     drivers
  * @brief       Driver for the SRF02 ultrasonic range sensor
- *
- * The connection between the MCU and the SRF02 is based on the i2c-interface.
- *
  * @{
  *
  * @file
  * @brief       Driver definitions for the SRF02 ultrasonic ranger.
  *
- * The connection between the SRF02 and the MCU is based on the i2c interface.
- *
  * @author      Zakaria Kasmi <zkasmi@inf.fu-berlin.de>
  * @author      Peter Kietzmann <peter.kietzmann@haw-hamburg.de>
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
  */
 
 #ifndef SRF02_H_
 #define SRF02_H_
 
-
 #include <stdint.h>
 #include "periph/i2c.h"
 
@@ -35,20 +31,13 @@
 extern "C" {
 #endif
 
-/** @brief The sensors default I2C address */
+/**
+ * @brief   Default I2C address of SRF02 sensors
+ */
 #define SRF02_DEFAULT_ADDR                  112
 
-/** @brief The command register which defines measurement mode */
-#define SRF02_COMMAND_REG                   0x0
-
-/** @brief The upper measurement byte */
-#define SRF02_RANGE_HIGH_BYTE               0x2
-
-/** @brief The lower measurement byte */
-#define SRF02_RANGE_LOW_BYTE                0x3
-
 /**
- * @brief Device descriptor for SRF02 sensors
+ * @brief   Device descriptor for SRF02 sensors
  */
 typedef struct {
     i2c_t i2c;               /**< I2C device the sensor is connected to */
@@ -56,45 +45,42 @@ typedef struct {
 } srf02_t;
 
 /**
- * @brief Possible measurement modes for the SRF02 sensor
+ * @brief   Possible measurement modes of the SRF02 sensor
  */
 typedef enum {
-    SRF02_MODE_REAL_INCH = 0x50,                   /**< result in inches */
-    SRF02_MODE_REAL_CM =   0x51,                   /**< result in centimeters */
-    SRF02_REAL_RANGING_MODE_MICRO_SEC = 0x52,      /**< result in microseconds */
-    SRF02_FAKE_RANGING_MODE_INCH =      0x56,      /**< synchronous measurement in inches */
-    SRF02_FAKE_RANGING_MODE_CM =        0x57,      /**< synchronous measurement in centimeters */
-    SRF02_FAKE_RANGING_MODE_MICRO_SEC = 0x58       /**< synchronous measurement in microseconds */
-}srf02_mode_t;
+    SRF02_MODE_REAL_INCH    = 0x50,     /**< result in inches */
+    SRF02_MODE_REAL_CM      = 0x51,     /**< result in centimeters */
+    SRF02_MODE_REAL_MS      = 0x52,     /**< result in microseconds */
+    SRF02_MODE_FAKE_INCH    = 0x56,     /**< result in inches (no pulse send) */
+    SRF02_MODE_FAKE_CM      = 0x57,     /**< result in cm (no pulse send) */
+    SRF02_MODE_FAKE_MS      = 0x58      /**< result in ms (no pulse send) */
+} srf02_mode_t;
 
 /**
- * @brief       Initialize the SRF02 ultrasonic sensor
+ * @brief   Initialize the SRF02 ultrasonic sensor
  *
  * @param[in] dev           device descriptor of an SRF02 sensor
  * @param[in] i2c           I2C device the sensor is connected to
  * @param[in] addr          I2C address of the sensor
- * @param[in] speed         I2C speed mode
  *
  * @return                  0 on successful initialization
- * @return                  -1 on undefined device given
- * @return                  -2 on unsupported speed value
+ * @return                  -1 on error
  */
-int srf02_init(srf02_t *dev, i2c_t i2c, uint8_t addr, i2c_speed_t speed);
+int srf02_init(srf02_t *dev, i2c_t i2c, uint8_t addr);
 
 /**
- * @brief       Get the distance measured from the SRF02 ultrasonic sensor
- *              The result of a ranging can be returned in inches,
- *              centimeters or microseconds
+ * @brief   Get the distance measured from the SRF02 ultrasonic sensor
+ *
+ * The result of the ranging operation is returned in inches, centimeters or
+ * microseconds - depending on the given @p mode parameter.
+ *
  * @param[in] dev           device descriptor of an SRF02 sensor
  * @param[in] mode          there are three real ranging modes, which return
  *                          the result in inches, centimeters or microseconds.
  *                          Another set of three fake ranging modes do the same
  *                          but without transmitting the burst
  *
- * @return                  -1 on undefined device given
- * @return the ranging result in inches, centimeters or microseconds. In the
- *         case of the fake ranging mode a zero value is returned. UINT16_MAX
- *         is returned if write/read action from the i2c-interface is failed.
+ * @return  the ranging result in inches, centimeters or microseconds
  *
  */
 uint16_t srf02_get_distance(srf02_t *dev, srf02_mode_t mode);
@@ -103,5 +89,5 @@ uint16_t srf02_get_distance(srf02_t *dev, srf02_mode_t mode);
 }
 #endif
 
-/** @} */
 #endif /* SRF02_H_ */
+/** @} */
diff --git a/drivers/srf02/srf02.c b/drivers/srf02/srf02.c
index 6994ceb9f4..953cdd7cf7 100644
--- a/drivers/srf02/srf02.c
+++ b/drivers/srf02/srf02.c
@@ -1,5 +1,6 @@
 /*
  * Copyright (C) 2013 Zakaria Kasmi <zkasmi@inf.fu-berlin.de>
+ *               2015 Freie Universität Berlin
  *
  * This file is subject to the terms and conditions of the GNU Lesser General
  * Public License v2.1. See the file LICENSE in the top level directory for more
@@ -11,91 +12,93 @@
  * @{
  *
  * @file
- * @brief       Driver for the SRF02 ultrasonic ranger.
- *              The connection between the MCU and the SRF02 is based on the
- *              i2c-interface.
+ * @brief       Driver for the SRF02 ultrasonic range sensor
  *
  * @author      Zakaria Kasmi <zkasmi@inf.fu-berlin.de>
  * @author      Peter Kietzmann <peter.kietzmann@haw-hamburg.de>
+ * @author      Hauke Petersen <hauke.petersen@fu-berlin.de>
  *
  * @}
  */
 
 #include <stdint.h>
 #include <stdio.h>
-#include "hwtimer.h"
+
+#include "xtimer.h"
 #include "srf02.h"
 #include "periph/i2c.h"
 
 #define ENABLE_DEBUG (0)
 #include "debug.h"
 
+/**
+ * @brief   The datasheet tells us, that ranging takes 70ms
+ */
+#define RANGE_DELAY         (70000U)
 
-int srf02_init(srf02_t *dev, i2c_t i2c, uint8_t addr, i2c_speed_t speed)
+/**
+ * @brief   Per default use normal speed on the I2C bus
+ */
+#define BUS_SPEED           (I2C_SPEED_NORMAL)
+
+/**
+ * @brief   SRF02 register addresses
+ * @{
+ */
+#define REG_CMD             (0x00)
+#define REG_HIGH            (0x02)
+#define REG_LOW             (0x03)
+#define REG_AUTO_HIGH       (0x04)
+#define REG_AUTO_LOW        (0x05)
+/** @} */
+
+int srf02_init(srf02_t *dev, i2c_t i2c, uint8_t addr)
 {
-    int status;
     dev->i2c = i2c;
     dev->addr = addr;
+    char rev;
 
     /* Acquire exclusive access to the bus. */
     i2c_acquire(dev->i2c);
     /* initialize i2c interface */
-    status =  i2c_init_master(dev->i2c, speed);
+    if (i2c_init_master(dev->i2c, BUS_SPEED) < 0) {
+        DEBUG("[srf02] error initializing I2C bus\n");
+        return -1;
+    }
+    /* try to read the software revision (read the CMD reg) from the device */
+    i2c_read_reg(i2c, addr, REG_CMD, &rev);
+    if (rev == 0 || rev == 255) {
+        DEBUG("[srf02] error reading the devices software revision\n");
+        return -1;
+    } else {
+        DEBUG("[srf02] software revision: 0x%02x\n", rev);
+    }
     /* Release the bus for other threads. */
     i2c_release(dev->i2c);
 
-    return status;
+    DEBUG("[srf02] initialization successful\n");
+    return 0;
 }
 
 uint16_t srf02_get_distance(srf02_t *dev, srf02_mode_t mode)
 {
-    int status;
-    char range_high_byte = 0;
-    char range_low_byte = 0;
-    uint16_t distance = 0;
+    char res[2];
 
-    /* Acquire exclusive access to the bus. */
+    /* trigger a new measurement by writing the mode to the CMD register */
+    DEBUG("[srf02] trigger new reading\n");
     i2c_acquire(dev->i2c);
-    /* initialize measure mode*/
-    status = i2c_write_reg(dev->i2c, dev->addr, SRF02_COMMAND_REG, mode);
-    /* Release the bus for other threads. */
+    i2c_write_reg(dev->i2c, dev->addr, REG_CMD, mode);
     i2c_release(dev->i2c);
 
-    if (status < 0) {
-        DEBUG("Write the ranging command to the i2c-interface is failed");
-        uint16_t distance = UINT16_MAX;
-        return distance;
-    }
+    /* give the sensor the required time for sampling */
+    xtimer_usleep(RANGE_DELAY);
 
-    hwtimer_wait(70000);
-
-    /* Acquire exclusive access to the bus. */
+    /* read the results */
     i2c_acquire(dev->i2c);
-    status = i2c_read_reg(dev->i2c, dev->addr,
-                      SRF02_RANGE_HIGH_BYTE, &range_high_byte);
-    /* Release the bus for other threads. */
+    i2c_read_regs(dev->i2c, dev->addr, REG_HIGH, res, 2);
     i2c_release(dev->i2c);
+    DEBUG("[srf02] result - high: 0x%02x low: 0x%02x\n", res[0], res[1]);
 
-    if (status < 0) {
-        DEBUG("Read the high echo byte from the i2c-interface is failed");
-        distance = UINT16_MAX;
-        return distance;
-    }
-
-    /* Acquire exclusive access to the bus. */
-    i2c_acquire(dev->i2c);
-    status = i2c_read_reg(dev->i2c, dev->addr,
-                      SRF02_RANGE_LOW_BYTE, &range_low_byte);
-    /* Release the bus for other threads. */
-    i2c_release(dev->i2c);
-
-    if (status < 0) {
-        DEBUG("Read the low echo byte from the i2c-interface is failed");
-        distance = UINT16_MAX;
-        return distance;
-    }
-
-    distance = (range_high_byte << 8) | (range_low_byte);
-
-    return distance;
+    /* compile result - TODO: fix for different host byte order other than LE */
+    return ((((uint16_t)res[0]) << 8) | (res[1] & 0xff));
 }
-- 
GitLab