src
examples
GrovePIRMotionSensor
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
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
{
32
t
.start();
33
34
nh
.initNode();
35
nh
.
advertise
(
pub_motion
);
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;
45
pub_motion
.
publish
(&
motion_msg
);
46
publisher_timer =
t
.read_ms() + 1000;
47
}
48
nh
.spinOnce();
49
}
50
}
51
ros::Publisher
main
int main()
Definition:
GrovePIRMotionSensor.cpp:30
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
nh
ros::NodeHandle nh
Definition:
GrovePIRMotionSensor.cpp:16
pub_motion
ros::Publisher pub_motion("motion", &motion_msg)
motion_msg
std_msgs::Bool motion_msg
Definition:
GrovePIRMotionSensor.cpp:18
t
Timer t
Definition:
GrovePIRMotionSensor.cpp:21
ros::NodeHandle
rosserial_mbed
Author(s): Gary Servin
autogenerated on Wed Mar 2 2022 00:58:08