src
examples
Clapper
Clapper.cpp
Go to the documentation of this file.
1
/*
2
* rosserial Clapper Example
3
*
4
* This code is a very simple example of the kinds of
5
* custom sensors that you can easily set up with rosserial
6
* and Mbed. This code uses a microphone attached to
7
* analog pin p20 detect two claps (2 loud sounds).
8
* You can use this clapper, for example, to command a robot
9
* in the area to come do your bidding.
10
*/
11
12
#include <ros.h>
13
#include <std_msgs/Empty.h>
14
15
#if defined(TARGET_LPC1768)
16
PinName mic = p20;
17
#elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
18
PinName mic = A0;
19
#else
20
#error "You need to specify a pin for the mic"
21
#endif
22
23
ros::NodeHandle
nh
;
24
25
std_msgs::Empty
clap_msg
;
26
ros::Publisher
p
(
"clap"
, &
clap_msg
);
27
28
enum
clapper_state
{
clap1
,
clap_one_waiting
,
pause
,
clap2
};
29
clapper_state
clap
;
30
31
int
volume_thresh
= 200;
//a clap sound needs to be:
32
//abs(clap_volume) > average noise + volume_thresh
33
AnalogIn
mic_pin
(mic);
34
int
adc_ave
=0;
35
36
Timer
t
;
37
int
main
() {
38
t
.start();
39
nh
.initNode();
40
41
nh
.
advertise
(
p
);
42
43
//measure the average volume of the noise in the area
44
for
(
int
i
=0;
i
<10;
i
++)
adc_ave
+=
mic_pin
.read_u16();
45
adc_ave
/= 10;
46
47
long
event_timer = 0;
48
49
while
(1) {
50
int
mic_val = 0;
51
for
(
int
i
=0;
i
<4;
i
++) mic_val +=
mic_pin
.read_u16();
52
53
mic_val = mic_val/4-
adc_ave
;
54
55
switch
(
clap
) {
56
case
clap1
:
57
if
(abs(mic_val) >
volume_thresh
) {
58
clap
=
clap_one_waiting
;
59
event_timer =
t
.read_ms();
60
}
61
break
;
62
case
clap_one_waiting
:
63
if
( (abs(mic_val) < 30) && ( (
t
.read_ms()- event_timer) > 20 ) ) {
64
clap
=
pause
;
65
event_timer =
t
.read_ms();
66
67
}
68
break
;
69
case
pause
:
// make sure there is a pause between
70
// the loud sounds
71
if
( mic_val >
volume_thresh
) {
72
clap
=
clap1
;
73
74
}
else
if
( (
t
.read_ms()-event_timer)> 60) {
75
clap
=
clap2
;
76
event_timer =
t
.read_ms();
77
78
}
79
break
;
80
case
clap2
:
81
if
(abs(mic_val) >
volume_thresh
) {
//we have got a double clap!
82
clap
=
clap1
;
83
p
.
publish
(&
clap_msg
);
84
}
else
if
( (
t
.read_ms()-event_timer)> 200) {
85
clap
=
clap1
;
// no clap detected, reset state machine
86
}
87
88
break
;
89
}
90
nh
.spinOnce();
91
}
92
}
93
ros::Publisher
i
int i
Definition:
ServiceServer.cpp:12
adc_ave
int adc_ave
Definition:
Clapper.cpp:34
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
volume_thresh
int volume_thresh
Definition:
Clapper.cpp:31
t
Timer t
Definition:
Clapper.cpp:36
nh
ros::NodeHandle nh
Definition:
Clapper.cpp:23
clap_one_waiting
@ clap_one_waiting
Definition:
Clapper.cpp:28
main
int main()
Definition:
Clapper.cpp:37
clap_msg
std_msgs::Empty clap_msg
Definition:
Clapper.cpp:25
clap1
@ clap1
Definition:
Clapper.cpp:28
p
ros::Publisher p("clap", &clap_msg)
clap
clapper_state clap
Definition:
Clapper.cpp:29
clapper_state
clapper_state
Definition:
Clapper.cpp:28
pause
@ pause
Definition:
Clapper.cpp:28
clap2
@ clap2
Definition:
Clapper.cpp:28
mic_pin
AnalogIn mic_pin(mic)
ros::NodeHandle
rosserial_mbed
Author(s): Gary Servin
autogenerated on Wed Mar 2 2022 00:58:08