(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

PIR Motion Sensor

Description: This tutorial shows an example for using an Mbed with a PIR Motion Sensor.

Tutorial Level: BEGINNER

Next Tutorial: DHT Humidity and Temperature Sensor

  Show EOL distros: 

rosserial allows you to easily integrate Mbed-based hardware with ROS. This tutorial will explain how to use a PIR Motion Sensor with an Mbed.

You will need an Mbed, a PIR Motion Sensor, and a way to connect your Sensor to your Mbed to your Mbed such as a breadboard, protoboard or Grove Base Shield.

The Code

Open the PIR Motion Sensor example placed on your previously downloaded rosserial/rosserial_mbed/examples directory, and open the GrovePIRMotionSensor.cpp file in your favorite text editor:

   1 /*
   2  * rosserial PIR Motion Sensor Example
   3  *
   4  * This tutorial demonstrates the usage of the
   5  * Seeedstudio PIR Motion Sensor Grove module
   6  * http://www.seeedstudio.com/depot/Grove-PIR-Motion-Sensor-p-802.html
   7  *
   8  * Source Code Based on:
   9  * https://developer.mbed.org/teams/Seeed/code/Seeed_Grove_PIR_Motion_Sensor_Example/
  10  */
  11 
  12 #include "mbed.h"
  13 #include <ros.h>
  14 #include <std_msgs/Bool.h>
  15 
  16 ros::NodeHandle  nh;
  17 
  18 std_msgs::Bool motion_msg;
  19 ros::Publisher pub_motion("motion", &motion_msg);
  20 
  21 Timer t;
  22 #ifdef TARGET_LPC1768
  23 DigitalIn sig1(p9);
  24 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
  25 DigitalIn sig1(D6);
  26 #else
  27 #error "You need to specify a pin for the sensor"
  28 #endif
  29 
  30 int main() {
  31     t.start();
  32 
  33     nh.initNode();
  34     nh.advertise(pub_motion);
  35 
  36     long publisher_timer = 0;
  37 
  38     while (1) {
  39 
  40         if (t.read_ms() > publisher_timer) {
  41             motion_msg.data = sig1;
  42             pub_motion.publish(&motion_msg);
  43             publisher_timer = t.read_ms() + 1000;
  44         }
  45         nh.spinOnce();
  46     }
  47 }

Compiling and uploading the Code

As seen on the previous tutorial, you must compile the source code by using the makefile in order to generate the .bin file that will be uploaded later to your MBED board. This is no different from uploading any other mbed binary.

Launching the App

Launch roscore

$ roscore

Run the serial node with the right serial port corresponding to your MBED board

$ rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0

$ rosrun rosserial_python serial_node.py /dev/ttyUSB0

Now watch the sensor's value on the pushed topic

$ rostopic echo /motion

Wiki: rosserial_mbed/Tutorials/PIR Motion Sensor (last edited 2016-01-04 20:53:30 by AlexisPojomovsky)