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