GrovePIRMotionSensor.cpp
Go to the documentation of this file.
00001 /*
00002  * rosserial PIR Motion Sensor Example
00003  *
00004  * This tutorial demonstrates the usage of the
00005  * Seeedstudio PIR Motion Sensor Grove module
00006  * http://www.seeedstudio.com/depot/Grove-PIR-Motion-Sensor-p-802.html
00007  *
00008  * Source Code Based on:
00009  * https://developer.mbed.org/teams/Seeed/code/Seeed_Grove_PIR_Motion_Sensor_Example/
00010  */
00011 
00012 #include "mbed.h"
00013 #include <ros.h>
00014 #include <std_msgs/Bool.h>
00015 
00016 ros::NodeHandle  nh;
00017 
00018 std_msgs::Bool motion_msg;
00019 ros::Publisher pub_motion("motion", &motion_msg);
00020 
00021 Timer t;
00022 #ifdef TARGET_LPC1768
00023 DigitalIn sig1(p9);
00024 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
00025 DigitalIn sig1(D6);
00026 #else
00027 #error "You need to specify a pin for the sensor"
00028 #endif
00029 
00030 int main()
00031 {
00032   t.start();
00033 
00034   nh.initNode();
00035   nh.advertise(pub_motion);
00036 
00037   long publisher_timer = 0;
00038 
00039   while (1)
00040   {
00041 
00042     if (t.read_ms() > publisher_timer)
00043     {
00044       motion_msg.data = sig1;
00045       pub_motion.publish(&motion_msg);
00046       publisher_timer = t.read_ms() + 1000;
00047     }
00048     nh.spinOnce();
00049   }
00050 }
00051 


rosserial_mbed
Author(s): Gary Servin
autogenerated on Sat Oct 7 2017 03:08:46