src
examples
GroveCollision
GroveCollision.cpp
Go to the documentation of this file.
1
/*
2
* rosserial Collission Sensor Example
3
*
4
* This tutorial demonstrates the usage of the
5
* Seeedstudio Collision Grove module
6
* http://www.seeedstudio.com/wiki/Grove_-_Collision_Sensor
7
*
8
* Source Code Based on:
9
* https://developer.mbed.org/components/Grove-Collision-Sensor/
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
collision_msg
;
19
ros::Publisher
pub_collision
(
"collision"
, &
collision_msg
);
20
21
22
Timer
t
;
23
#ifdef TARGET_LPC1768
24
DigitalIn sig1(p9);
25
#elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
26
DigitalIn sig1(D6);
27
#else
28
#error "You need to specify a pin for the sensor"
29
#endif
30
31
int
main
()
32
{
33
t
.start();
34
35
nh
.initNode();
36
nh
.
advertise
(
pub_collision
);
37
38
long
publisher_timer = 0;
39
40
while
(1)
41
{
42
43
if
(
t
.read_ms() > publisher_timer)
44
{
45
collision_msg
.data = !sig1;
46
pub_collision
.
publish
(&
collision_msg
);
47
publisher_timer =
t
.read_ms() + 1000;
48
}
49
nh
.spinOnce();
50
}
51
}
52
ros::Publisher
pub_collision
ros::Publisher pub_collision("collision", &collision_msg)
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
t
Timer t
Definition:
GroveCollision.cpp:22
collision_msg
std_msgs::Bool collision_msg
Definition:
GroveCollision.cpp:18
nh
ros::NodeHandle nh
Definition:
GroveCollision.cpp:16
main
int main()
Definition:
GroveCollision.cpp:31
ros::NodeHandle
rosserial_mbed
Author(s): Gary Servin
autogenerated on Wed Mar 2 2022 00:58:08