GrovePIRMotionSensor.cpp
Go to the documentation of this file.
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 
17 
18 std_msgs::Bool 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 {
32  t.start();
33 
34  nh.initNode();
36 
37  long publisher_timer = 0;
38 
39  while (1)
40  {
41 
42  if (t.read_ms() > publisher_timer)
43  {
44  motion_msg.data = sig1;
46  publisher_timer = t.read_ms() + 1000;
47  }
48  nh.spinOnce();
49  }
50 }
51 
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle nh
Timer t
int main()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
std_msgs::Bool motion_msg
ros::Publisher pub_motion("motion",&motion_msg)


rosserial_mbed
Author(s): Gary Servin
autogenerated on Fri Jun 7 2019 22:02:48