Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012 #include "mbed.h"
00013 #include <ros.h>
00014 #include <std_msgs/Float32MultiArray.h>
00015
00016 ros::NodeHandle nh;
00017
00018 #ifdef TARGET_LPC1768
00019 PwmOut buzzer(p21);
00020 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
00021 PwmOut buzzer(D2);
00022 #else
00023 #error "You need to specify a pin for the sensor"
00024 #endif
00025
00026 Timeout toff;
00027 bool playing = false;
00028 DigitalOut led(LED1);
00029
00030 void nobeep()
00031 {
00032 buzzer.write(0.0);
00033 led = 1;
00034 playing = false;
00035 }
00036 void beep(float freq, float time)
00037 {
00038 buzzer.period(1.0 / freq);
00039 buzzer.write(0.5);
00040 toff.attach(nobeep, time);
00041 led = 0;
00042 }
00043
00044 void messageCb(const std_msgs::Float32MultiArray& msg)
00045 {
00046 if (!playing)
00047 {
00048 playing = true;
00049
00050
00051 beep(msg.data[0], msg.data[1]);
00052 }
00053 }
00054
00055 ros::Subscriber<std_msgs::Float32MultiArray> sub("buzzer", &messageCb);
00056
00057 int main()
00058 {
00059 buzzer = 0;
00060 led = 1;
00061 nh.initNode();
00062 nh.subscribe(sub);
00063 while (1)
00064 {
00065 nh.spinOnce();
00066 wait_ms(1);
00067 }
00068 }