From 0c5c3d9b77d3fea9c2fd041b5c614101025a61eb Mon Sep 17 00:00:00 2001
From: Hyungsin <hskim@berkeley.edu>
Date: Tue, 26 Jun 2018 13:46:37 -0700
Subject: [PATCH] driver/pir: add pir-based occupancy sensing

---
 drivers/Makefile.dep               |  5 ++
 drivers/Makefile.include           |  4 ++
 drivers/include/pir.h              | 50 +++++++++++++++--
 drivers/include/saul.h             |  1 +
 drivers/pir/include/pir_params.h   | 71 +++++++++++++++++++++++
 drivers/pir/pir.c                  | 90 +++++++++++++++++++++++++++---
 drivers/pir/pir_saul.c             | 42 ++++++++++++++
 drivers/saul/saul_str.c            |  1 +
 sys/auto_init/auto_init.c          |  4 ++
 sys/auto_init/saul/auto_init_pir.c | 71 +++++++++++++++++++++++
 tests/driver_pir/Makefile          | 12 ++--
 tests/driver_pir/README.md         |  6 +-
 tests/driver_pir/main.c            | 18 +++---
 13 files changed, 345 insertions(+), 30 deletions(-)
 create mode 100644 drivers/pir/include/pir_params.h
 create mode 100644 drivers/pir/pir_saul.c
 create mode 100644 sys/auto_init/saul/auto_init_pir.c

diff --git a/drivers/Makefile.dep b/drivers/Makefile.dep
index d9bed242d2..48f58ce295 100644
--- a/drivers/Makefile.dep
+++ b/drivers/Makefile.dep
@@ -279,6 +279,11 @@ ifneq (,$(filter pcd8544,$(USEMODULE)))
   USEMODULE += xtimer
 endif
 
+ifneq (,$(filter pir,$(USEMODULE)))
+  FEATURES_REQUIRED += periph_gpio
+  USEMODULE += xtimer
+endif
+
 ifneq (,$(filter rgbled,$(USEMODULE)))
   USEMODULE += color
 endif
diff --git a/drivers/Makefile.include b/drivers/Makefile.include
index 8c7a1c4482..7bf9964085 100644
--- a/drivers/Makefile.include
+++ b/drivers/Makefile.include
@@ -186,6 +186,10 @@ ifneq (,$(filter pcd8544,$(USEMODULE)))
   USEMODULE_INCLUDES += $(RIOTBASE)/drivers/pcd8544/include
 endif
 
+ifneq (,$(filter pir,$(USEMODULE)))
+  USEMODULE_INCLUDES += $(RIOTBASE)/drivers/pir/include
+endif
+
 ifneq (,$(filter pulse_counter,$(USEMODULE)))
   USEMODULE_INCLUDES += $(RIOTBASE)/drivers/pulse_counter/include
 endif
diff --git a/drivers/include/pir.h b/drivers/include/pir.h
index ac1f6fd174..e0be71234d 100644
--- a/drivers/include/pir.h
+++ b/drivers/include/pir.h
@@ -16,6 +16,7 @@
  * @brief       Device driver interface for the PIR motion sensor
  *
  * @author      Ludwig Knüpfer <ludwig.knuepfer@fu-berlin.de>
+ * @author      Hyung-Sin Kim <hs.kim@cs.berkeley.edu>
  */
 
 #ifndef PIR_H
@@ -23,17 +24,41 @@
 
 #include "kernel_types.h"
 #include "periph/gpio.h"
+#include "stdbool.h"
 
 #ifdef __cplusplus
 extern "C" {
 #endif
 
+/**
+ * @brief   PIR specific return values
+ */
+enum {
+    PIR_OK       = 0,     /**< everything went as expected */
+    PIR_NOGPIO   = -1,    /**< errors while initializing the GPIO */
+    PIR_NOTHREAD = -2,    /**< errors while registering the thread */
+    PIR_TIMEERR  = -3,    /**< errors while getting the time information */
+};
+
+/**
+ * @brief   Parameters needed for device initialization
+ */
+typedef struct {
+    gpio_t gpio;      /**< GPIO device which is used */
+    bool active_high; /**< Active when GPIO pin is high or not */
+} pir_params_t;
+
+
 /**
  * @brief   device descriptor for a PIR sensor
  */
 typedef struct {
-    gpio_t          gpio_dev;       /**< GPIO device which is used */
-    kernel_pid_t    msg_thread_pid; /**< thread to msg on irq */
+    uint64_t start_active_time;  /**< Time when PIR starts to be active */
+    uint64_t accum_active_time;  /**< Accumulated active time */
+    uint64_t last_read_time;     /**< Last time when PIR status is read */
+    kernel_pid_t msg_thread_pid; /**< thread to msg on irq */
+    bool active;                 /**< Indicate PIR is active or not */
+    pir_params_t p;              /**< Configuration parameters */
 } pir_t;
 
 /**
@@ -47,8 +72,8 @@ typedef struct {
  * @brief   event type for a PIR sensor
  */
 typedef enum {
-    PIR_STATUS_HI = PIR_MSG_T_STATUS_START,     /**< motion was detected */
-    PIR_STATUS_LO,                              /**< no motion is detected */
+    PIR_STATUS_ACTIVE = PIR_MSG_T_STATUS_START,   /**< motion was detected */
+    PIR_STATUS_INACTIVE,                          /**< no motion is detected */
 } pir_event_t;
 
 /**
@@ -62,12 +87,12 @@ typedef enum {
  * measurements can be made.
  *
  * @param[out] dev      device descriptor of an PIR sensor
- * @param[in] gpio      the GPIO device the sensor is connected to
+ * @param[in] params    parameters of the PIR sensor
  *
  * @return              0 on success
  * @return              -1 on error
  */
-int pir_init(pir_t *dev, gpio_t gpio);
+int pir_init(pir_t *dev, const pir_params_t* params);
 
 /**
  * @brief   Read the current status of the motion sensor
@@ -78,6 +103,19 @@ int pir_init(pir_t *dev, gpio_t gpio);
  */
 pir_event_t pir_get_status(const pir_t *dev);
 
+/**
+ * @brief   Read OCCUPANCY value
+ *
+ * @param[in] dev       device descriptor of the PIR motion sensor to read from
+ * @param[out] occup    occupancy ratio [in 100 * percentage]
+ *                      The value is renewed when it is read. So it is percentage
+ *                      of occupancy since the last read.
+ *
+ * @return              0 on success,
+ * @return              -1 on errors,
+ */
+int pir_get_occupancy(pir_t *dev, int16_t *occup);
+
 /**
  * @brief   Register a thread for notification whan state changes on the
  *          motion sensor.
diff --git a/drivers/include/saul.h b/drivers/include/saul.h
index 6bc40036b3..c678d6b19f 100644
--- a/drivers/include/saul.h
+++ b/drivers/include/saul.h
@@ -96,6 +96,7 @@ enum {
     SAUL_SENSE_DISTANCE = 0x8e,     /**< sensor: distance */
     SAUL_SENSE_CO2      = 0x8f,     /**< sensor: CO2 Gas */
     SAUL_SENSE_TVOC     = 0x90,     /**< sensor: TVOC Gas */
+    SAUL_SENSE_OCCUP    = 0x91,     /**< sensor: occupancy */
     SAUL_CLASS_ANY      = 0xff      /**< any device - wildcard */
     /* extend this list as needed... */
 };
diff --git a/drivers/pir/include/pir_params.h b/drivers/pir/include/pir_params.h
new file mode 100644
index 0000000000..cca0ae8d26
--- /dev/null
+++ b/drivers/pir/include/pir_params.h
@@ -0,0 +1,71 @@
+/*
+ * Copyright (C) 2018 UC Berkeley
+ *
+ * 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 details.
+ */
+
+/**
+ * @ingroup     drivers_pir
+ *
+ * @{
+ * @file
+ * @brief       Default configuration for PIR devices
+ *
+ * @author      Hyung-Sin Kim <hs.kim@cs.berkeley.edu>
+ */
+
+#ifndef PIR_PARAMS_H
+#define PIR_PARAMS_H
+
+#include "board.h"
+#include "pir.h"
+#include "saul_reg.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @brief   Set default configuration parameters for the PIR driver
+ * @{
+ */
+#ifndef PIR_PARAM_GPIO
+#define PIR_PARAM_GPIO             GPIO_PIN(0, 6)
+#endif
+#ifndef PIR_PARAM_ACTIVE_HIGH
+#define PIR_PARAM_ACTIVE_HIGH      1
+#endif
+
+#ifndef PIR_PARAMS
+#define PIR_PARAMS                 { .gpio = PIR_PARAM_GPIO, \
+                                     .active_high = PIR_PARAM_ACTIVE_HIGH }
+#endif
+#ifndef PIR_SAUL_INFO
+#define PIR_SAUL_INFO              { .name = "pir" }
+#endif
+/**@}*/
+
+/**
+ * @brief   PIR configuration
+ */
+static const pir_params_t pir_params[] =
+{
+    PIR_PARAMS
+};
+
+/**
+ * @brief   Additional meta information to keep in the SAUL registry
+ */
+static const saul_reg_info_t pir_saul_info[] =
+{
+    PIR_SAUL_INFO
+};
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* PIR_PARAMS_H */
+/** @} */
diff --git a/drivers/pir/pir.c b/drivers/pir/pir.c
index 1f4ac527d4..2f01afe69b 100644
--- a/drivers/pir/pir.c
+++ b/drivers/pir/pir.c
@@ -1,5 +1,6 @@
 /*
  * Copyright (C) 2014 Freie Universität Berlin
+ * Copyright (C) 2018 UC Berkeley
  *
  * 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
@@ -14,13 +15,16 @@
  * @brief       Device driver implementation for the PIR motion sensor
  *
  * @author      Ludwig Knüpfer <ludwig.knuepfer@fu-berlin.de>
+ * @author      Hyung-Sin Kim <hs.kim@cs.berkeley.edu>
  *
  * @}
  */
 
 #include "pir.h"
+#include "irq.h"
 #include "thread.h"
 #include "msg.h"
+#include "xtimer.h"
 
 #define ENABLE_DEBUG (0)
 #include "debug.h"
@@ -37,16 +41,56 @@ static void pir_send_msg(pir_t *dev, pir_event_t event);
  * public API implementation
  **********************************************************************/
 
-int pir_init(pir_t *dev, gpio_t gpio)
+int pir_init(pir_t *dev, const pir_params_t *params)
 {
-    dev->gpio_dev = gpio;
+    dev->p.gpio = params->gpio;
+    dev->p.active_high = params->active_high;
     dev->msg_thread_pid = KERNEL_PID_UNDEF;
-    return gpio_init(dev->gpio_dev, GPIO_IN);
+
+    dev->active = false;
+    dev->accum_active_time = 0;
+    dev->start_active_time = 0;
+    dev->last_read_time = xtimer_now_usec64();
+
+    gpio_mode_t gpio_mode;
+    if (dev->p.active_high) {
+        gpio_mode = GPIO_IN_PD;
+    }
+    else {
+        gpio_mode = GPIO_IN_PU;
+    }
+
+    if (gpio_init_int(dev->p.gpio, gpio_mode, GPIO_BOTH, pir_callback, dev)) {
+        return PIR_NOGPIO;
+    }
+    return PIR_OK;
 }
 
 pir_event_t pir_get_status(const pir_t *dev)
 {
-    return ((gpio_read(dev->gpio_dev) == 0) ? PIR_STATUS_LO : PIR_STATUS_HI);
+    return (((gpio_read(dev->p.gpio) > 0) == dev->p.active_high) ?
+            PIR_STATUS_ACTIVE : PIR_STATUS_INACTIVE);
+}
+
+int pir_get_occupancy(pir_t *dev, int16_t *occup) {
+    int irq_state = irq_disable();
+    uint64_t now = xtimer_now_usec64();
+    uint64_t total_time = now - dev->last_read_time;
+    if (total_time == 0) {
+        irq_restore(irq_state);
+        return PIR_TIMEERR;
+    }
+
+    /* We were busy counting */
+    if (dev->active) {
+        dev->accum_active_time += (now - dev->start_active_time);
+        dev->start_active_time = now;
+    }
+    *occup = (int16_t)((dev->accum_active_time * 10000) / total_time);
+    dev->last_read_time = now;
+    dev->accum_active_time = 0;
+    irq_restore(irq_state);
+    return PIR_OK;
 }
 
 int pir_register_thread(pir_t *dev)
@@ -54,20 +98,20 @@ int pir_register_thread(pir_t *dev)
     if (dev->msg_thread_pid != KERNEL_PID_UNDEF) {
         if (dev->msg_thread_pid != thread_getpid()) {
             DEBUG("pir_register_thread: already registered to another thread\n");
-            return -2;
+            return PIR_NOTHREAD;
         }
     }
     else {
         DEBUG("pir_register_thread: activating interrupt for %p..\n", (void *)dev);
-        if (pir_activate_int(dev) != 0) {
+        if (pir_activate_int(dev) != PIR_OK) {
             DEBUG("\tfailed\n");
-            return -1;
+            return PIR_NOGPIO;
         }
         DEBUG("\tsuccess\n");
     }
     dev->msg_thread_pid = thread_getpid();
 
-    return 0;
+    return PIR_OK;
 }
 
 /**********************************************************************
@@ -100,6 +144,23 @@ static void pir_callback(void *arg)
 {
     DEBUG("pir_callback: %p\n", arg);
     pir_t *dev = (pir_t*) arg;
+    bool pin_now = gpio_read(dev->p.gpio);
+    uint64_t now = xtimer_now_usec64();
+
+    /* We were busy counting */
+    if (dev->active) {
+        /* Add into accumulation */
+        dev->accum_active_time += (now - dev->start_active_time);
+    }
+    /* Pin is rising */
+    if (pin_now == dev->p.active_high) {
+        dev->start_active_time = now;
+        dev->active = true;
+    /* Pin is falling */
+    } else {
+        dev->active = false;
+    }
+
     if (dev->msg_thread_pid != KERNEL_PID_UNDEF) {
         pir_send_msg(dev, pir_get_status(dev));
     }
@@ -107,5 +168,16 @@ static void pir_callback(void *arg)
 
 static int pir_activate_int(pir_t *dev)
 {
-    return gpio_init_int(dev->gpio_dev, GPIO_IN, GPIO_BOTH, pir_callback, dev);
+    gpio_mode_t gpio_mode;
+    if (dev->p.active_high) {
+        gpio_mode = GPIO_IN_PD;
+    }
+    else {
+        gpio_mode = GPIO_IN_PU;
+    }
+
+    if (gpio_init_int(dev->p.gpio, gpio_mode, GPIO_BOTH, pir_callback, dev)) {
+        return PIR_NOGPIO;
+    }
+    return PIR_OK;
 }
diff --git a/drivers/pir/pir_saul.c b/drivers/pir/pir_saul.c
new file mode 100644
index 0000000000..eea97f6e3a
--- /dev/null
+++ b/drivers/pir/pir_saul.c
@@ -0,0 +1,42 @@
+/*
+ * Copyright (C) 2018 UC Berkeley
+ *
+ * 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 details.
+ */
+
+/**
+ * @ingroup     drivers_pir
+ * @{
+ *
+ * @file
+ * @brief       PIR adaption to the RIOT actuator/sensor interface
+ *
+ * @author      Hyung-Sin Kim <hs.kim@cs.berkeley.edu>
+ *
+ * @}
+ */
+
+#include <string.h>
+
+#include "saul.h"
+#include "pir.h"
+
+static int read_occup(const void *dev, phydat_t *res) {
+    pir_t *d = (pir_t *)dev;
+    if (pir_get_occupancy(d, &(res->val[0]))) {
+        /* Read failure */
+        return -ECANCELED;
+    }
+    memset(&(res->val[1]), 0, 2 * sizeof(int16_t));
+    res->unit = UNIT_PERCENT;
+    res->scale = -2;
+    return 1;
+}
+
+const saul_driver_t pir_saul_occup_driver = {
+    .read = read_occup,
+    .write = saul_notsup,
+    .type = SAUL_SENSE_OCCUP,
+};
diff --git a/drivers/saul/saul_str.c b/drivers/saul/saul_str.c
index 3f66582bd2..255037d879 100644
--- a/drivers/saul/saul_str.c
+++ b/drivers/saul/saul_str.c
@@ -54,6 +54,7 @@ const char *saul_class_to_str(const uint8_t class_id)
         case SAUL_SENSE_CO2:       return "SENSE_CO2";
         case SAUL_SENSE_TVOC:      return "SENSE_TVOC";
         case SAUL_CLASS_ANY:       return "CLASS_ANY";
+        case SAUL_SENSE_OCCUP:     return "SENSE_OCCUP";
         default:                   return "CLASS_UNKNOWN";
     }
 }
diff --git a/sys/auto_init/auto_init.c b/sys/auto_init/auto_init.c
index 067b367e85..8287a2568c 100644
--- a/sys/auto_init/auto_init.c
+++ b/sys/auto_init/auto_init.c
@@ -330,6 +330,10 @@ auto_init_mpu9150();
     extern void auto_init_grove_ledbar(void);
     auto_init_grove_ledbar();
 #endif
+#ifdef MODULE_PIR
+    extern void auto_init_pir(void);
+    auto_init_pir();
+#endif
 #ifdef MODULE_SI70XX
     extern void auto_init_si70xx(void);
     auto_init_si70xx();
diff --git a/sys/auto_init/saul/auto_init_pir.c b/sys/auto_init/saul/auto_init_pir.c
new file mode 100644
index 0000000000..d01b1217c6
--- /dev/null
+++ b/sys/auto_init/saul/auto_init_pir.c
@@ -0,0 +1,71 @@
+/*
+ * Copyright (C) 2018 UC Berkeley
+ *
+ * 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 details.
+ *
+ */
+
+/*
+ * @ingroup     sys_auto_init_saul
+ * @{
+ *
+ * @file
+ * @brief       Auto initialization for PIR devices
+ *
+ * @author      Hyung-Sin Kim <hs.kim@cs.berkeley.edu>
+ *
+ * @}
+ */
+
+#ifdef MODULE_PIR
+
+#include "log.h"
+#include "saul_reg.h"
+#include "pir_params.h"
+
+/**
+ * @brief   Define the number of configured sensors
+ */
+#define PIR_NUM    (sizeof(pir_params)/sizeof(pir_params[0]))
+
+/**
+ * @brief   Allocate memory for the device descriptors
+ */
+static pir_t pir_devs[PIR_NUM];
+
+/**
+ * @brief   Memory for the SAUL registry entries
+ */
+static saul_reg_t saul_entries[PIR_NUM];
+
+/**
+ * @brief   Reference to the occupancy driver struct
+ * @{
+ */
+extern saul_driver_t pir_saul_occup_driver;
+/** @} */
+
+
+void auto_init_pir(void)
+{
+    for (unsigned i = 0; i < PIR_NUM; i++) {
+        LOG_DEBUG("[auto_init_saul] initializing pir #%u\n", i);
+
+        int res = pir_init(&pir_devs[i], &pir_params[i]);
+        if (res != 0) {
+            LOG_ERROR("[auto_init_saul] error initializing pir #%u\n", i);
+        }
+        else {
+            saul_entries[i].dev = &(pir_devs[i]);
+            saul_entries[i].name = pir_saul_info[i].name;
+            saul_entries[i].driver = &pir_saul_occup_driver;
+            saul_reg_add(&(saul_entries[i]));
+        }
+    }
+}
+
+#else
+typedef int dont_be_pedantic;
+#endif /* MODULE_PIR */
diff --git a/tests/driver_pir/Makefile b/tests/driver_pir/Makefile
index 54ca113e5b..47ddf2c560 100644
--- a/tests/driver_pir/Makefile
+++ b/tests/driver_pir/Makefile
@@ -9,17 +9,21 @@ USEMODULE += xtimer
 
 # define parameters for selected boards
 ifneq (,$(filter stm32f4discovery,$(BOARD)))
-  PIR_GPIO ?= GPIO_PIN\(3,7\)
+  PIR_PARAM_GPIO ?= GPIO_PIN\(3,7\)
+  PIR_PARAM_ACTIVE_HIGH ?= 1
 endif
 ifneq (,$(filter arduino-due,$(BOARD)))
-  PIR_GPIO ?= GPIO_PIN\(0,20\)
+  PIR_PARAM_GPIO ?= GPIO_PIN\(0,20\)
+  PIR_PARAM_ACTIVE_HIGH ?= 1
 endif
 
 # set default device parameters in case they are undefined
-PIR_GPIO ?= GPIO_PIN\(0,0\)
+PIR_PARAM_GPIO ?= GPIO_PIN\(0,0\)
+PIR_PARAM_ACTIVE_HIGH ?= 1
 
 # export parameters
-CFLAGS += -DPIR_GPIO=$(PIR_GPIO)
+CFLAGS += -DPIR_PARAM_GPIO=$(PIR_PARAM_GPIO)
+CFLAGS += -DPIR_PARAM_ACTIVE_HIGH=$(PIR_PARAM_ACTIVE_HIGH)
 
 include $(RIOTBASE)/Makefile.include
 
diff --git a/tests/driver_pir/README.md b/tests/driver_pir/README.md
index 108a479c59..6121fb7a82 100644
--- a/tests/driver_pir/README.md
+++ b/tests/driver_pir/README.md
@@ -16,7 +16,8 @@ configured to create interrupts.
 Compile and flash this test application like:
 
     export BOARD=your_board
-    export PIR_GPIO=name_of_your_pin
+    export PIR_PARAM_GPIO=name_of_your_pin
+    export PIR_PARAM_ACTIVE_HIGH=if_gpio_pin_is_high_or_low_when_pir_is_active
     make clean
     make all-interrupt
     make flash
@@ -40,7 +41,8 @@ Connect the sensor's "out" pin to any GPIO pin of you board.
 Compile and flash this test application like:
 
     export BOARD=your_board
-    export PIR_GPIO=name_of_your_pin
+    export PIR_PARAM_GPIO=name_of_your_pin
+    export PIR_PARAM_ACTIVE_HIGH=if_gpio_pin_is_high_or_low_when_pir_is_active
     make clean
     make all-polling
     make flash
diff --git a/tests/driver_pir/main.c b/tests/driver_pir/main.c
index 14bf822071..63736db54d 100644
--- a/tests/driver_pir/main.c
+++ b/tests/driver_pir/main.c
@@ -1,5 +1,6 @@
 /*
  * Copyright (C) 2014 Freie Universität Berlin
+ * Copyright (C) 2018 UC Berkeley
  *
  * 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
@@ -14,19 +15,17 @@
  * @brief       Test application for the PIR motion sensor driver
  *
  * @author      Ludwig Knüpfer <ludwig.knuepfer@fu-berlin.de>
+ * @author      Hyung-Sin Kim <hs.kim@cs.berkeley.edu>
  *
  * @}
  */
 
-#ifndef PIR_GPIO
-#error "PIR_GPIO not defined"
-#endif
-
 #include <stdio.h>
 
 #include "thread.h"
 #include "xtimer.h"
 #include "pir.h"
+#include "pir_params.h"
 
 static char pir_handler_stack[THREAD_STACKSIZE_MAIN];
 static pir_t dev;
@@ -44,10 +43,10 @@ void* pir_handler(void *arg)
     while (msg_receive(&m)) {
         printf("PIR handler got a message: ");
         switch (m.type) {
-            case PIR_STATUS_HI:
+            case PIR_STATUS_ACTIVE:
                 puts("something started moving.");
                 break;
-            case PIR_STATUS_LO:
+            case PIR_STATUS_INACTIVE:
                 puts("the movement has ceased.");
                 break;
             default:
@@ -63,8 +62,8 @@ void* pir_handler(void *arg)
 int main(void)
 {
     puts("PIR motion sensor test application\n");
-    printf("Initializing PIR sensor at GPIO_%ld... ", (long)PIR_GPIO);
-    if (pir_init(&dev, PIR_GPIO) == 0) {
+    printf("Initializing PIR sensor at GPIO_%ld... ", (long)PIR_PARAM_GPIO);
+    if (pir_init(&dev, &pir_params[0]) == 0) {
         puts("[OK]\n");
     }
     else {
@@ -75,7 +74,8 @@ int main(void)
 #if TEST_PIR_POLLING
     puts("Printing sensor state every second.");
     while (1) {
-        printf("Status: %s\n", pir_get_status(&dev) == PIR_STATUS_LO ? "lo" : "hi");
+        printf("Status: %s\n", pir_get_status(&dev) == PIR_STATUS_INACTIVE ?
+               "inactive" : "active");
         xtimer_usleep(1000 * 1000);
     }
 #else
-- 
GitLab