Clapper.cpp
Go to the documentation of this file.
00001 /*
00002  * rosserial Clapper Example
00003  *
00004  * This code is a very simple example of the kinds of
00005  * custom sensors that you can easily set up with rosserial
00006  * and Mbed.  This code uses a microphone attached to
00007  * analog pin p20 detect two claps (2 loud sounds).
00008  * You can use this clapper, for example, to command a robot
00009  * in the area to come do your bidding.
00010  */
00011 
00012 #include <ros.h>
00013 #include <std_msgs/Empty.h>
00014 
00015 #if defined(TARGET_LPC1768)
00016 PinName mic = p20;
00017 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
00018 PinName mic = A0;
00019 #else
00020 #error "You need to specify a pin for the mic"
00021 #endif
00022 
00023 ros::NodeHandle  nh;
00024 
00025 std_msgs::Empty clap_msg;
00026 ros::Publisher p("clap", &clap_msg);
00027 
00028 enum clapper_state { clap1, clap_one_waiting,  pause, clap2};
00029 clapper_state clap;
00030 
00031 int volume_thresh = 200;  //a clap sound needs to be:
00032 //abs(clap_volume) > average noise + volume_thresh
00033 AnalogIn mic_pin(mic);
00034 int adc_ave=0;
00035 
00036 Timer t;
00037 int main() {
00038     t.start();
00039     nh.initNode();
00040 
00041     nh.advertise(p);
00042 
00043     //measure the average volume of the noise in the area
00044     for (int i =0; i<10; i++) adc_ave += mic_pin.read_u16();
00045     adc_ave /= 10;
00046 
00047     long event_timer = 0;
00048 
00049     while (1) {
00050         int mic_val = 0;
00051         for (int i=0; i<4; i++) mic_val += mic_pin.read_u16();
00052 
00053         mic_val = mic_val/4-adc_ave;
00054 
00055         switch (clap) {
00056             case clap1:
00057                 if (abs(mic_val) > volume_thresh) {
00058                     clap = clap_one_waiting;
00059                     event_timer = t.read_ms();
00060                 }
00061                 break;
00062             case clap_one_waiting:
00063                 if ( (abs(mic_val) < 30) && ( (t.read_ms()- event_timer) > 20 ) ) {
00064                     clap= pause;
00065                     event_timer = t.read_ms();
00066 
00067                 }
00068                 break;
00069             case pause: // make sure there is a pause between
00070                 // the loud sounds
00071                 if ( mic_val > volume_thresh) {
00072                     clap = clap1;
00073 
00074                 } else if ( (t.read_ms()-event_timer)> 60)  {
00075                     clap = clap2;
00076                     event_timer = t.read_ms();
00077 
00078                 }
00079                 break;
00080             case clap2:
00081                 if (abs(mic_val) > volume_thresh) { //we have got a double clap!
00082                     clap = clap1;
00083                     p.publish(&clap_msg);
00084                 } else if ( (t.read_ms()-event_timer)> 200) {
00085                     clap= clap1; // no clap detected, reset state machine
00086                 }
00087 
00088                 break;
00089         }
00090         nh.spinOnce();
00091     }
00092 }
00093 


rosserial_mbed
Author(s): Gary Servin
autogenerated on Sat Oct 7 2017 03:08:46