src
examples
GroveBuzzer
GroveBuzzer.cpp
Go to the documentation of this file.
1
/*
2
* rosserial Buzzer Module Example
3
*
4
* This tutorial demonstrates the usage of the
5
* Seeedstudio Buzzer Grove module
6
* http://www.seeedstudio.com/depot/Grove-Buzzer-p-768.html
7
*
8
* Source Code Based on:
9
* https://developer.mbed.org/teams/Seeed/code/Seeed_Grove_Buzzer/
10
*/
11
12
#include "mbed.h"
13
#include <ros.h>
14
#include <std_msgs/Float32MultiArray.h>
15
16
ros::NodeHandle
nh
;
17
18
#ifdef TARGET_LPC1768
19
PwmOut buzzer(p21);
20
#elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
21
PwmOut buzzer(D2);
22
#else
23
#error "You need to specify a pin for the sensor"
24
#endif
25
26
Timeout
toff
;
27
bool
playing
=
false
;
28
DigitalOut
led
(LED1);
29
30
void
nobeep
()
31
{
32
buzzer.write(0.0);
33
led
= 1;
34
playing
=
false
;
35
}
36
void
beep
(
float
freq,
float
time)
37
{
38
buzzer.period(1.0 / freq);
39
buzzer.write(0.5);
40
toff
.attach(
nobeep
, time);
41
led
= 0;
42
}
43
44
void
messageCb
(
const
std_msgs::Float32MultiArray& msg)
45
{
46
if
(!
playing
)
47
{
48
playing
=
true
;
49
// msg.data[0] - Note
50
// msg.data[1] - duration in seconds
51
beep
(msg.data[0], msg.data[1]);
52
}
53
}
54
55
ros::Subscriber<std_msgs::Float32MultiArray>
sub
(
"buzzer"
, &
messageCb
);
56
57
int
main
()
58
{
59
buzzer = 0;
60
led
= 1;
61
nh
.initNode();
62
nh
.
subscribe
(
sub
);
63
while
(1)
64
{
65
nh
.spinOnce();
66
wait_ms(1);
67
}
68
}
nobeep
void nobeep()
Definition:
GroveBuzzer.cpp:30
sub
ros::Subscriber< std_msgs::Float32MultiArray > sub("buzzer", &messageCb)
messageCb
void messageCb(const std_msgs::Float32MultiArray &msg)
Definition:
GroveBuzzer.cpp:44
led
DigitalOut led(LED1)
playing
bool playing
Definition:
GroveBuzzer.cpp:27
beep
void beep(float freq, float time)
Definition:
GroveBuzzer.cpp:36
main
int main()
Definition:
GroveBuzzer.cpp:57
ros::NodeHandle::subscribe
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
nh
ros::NodeHandle nh
Definition:
GroveBuzzer.cpp:16
toff
Timeout toff
Definition:
GroveBuzzer.cpp:26
ros::Subscriber
ros::NodeHandle
rosserial_mbed
Author(s): Gary Servin
autogenerated on Wed Mar 2 2022 00:58:08