(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

Buzzer Module

Description: This tutorial will cover the use of an Mbed with a Buzzer Module.

Tutorial Level: BEGINNER

Next Tutorial: Collision Sensor

  Show EOL distros: 

rosserial allows you to easily integrate Mbed-based hardware with ROS. This tutorial will explain how to use a Buzzer Module with a Mbed.

You will need an Mbed, a Buzzer, and a way to connect your Buzzer to your Mbed such as a breadboard, protoboard or Grove Base Shield.

The Code

Open the Buzzer example placed on your previously downloaded rosserial/rosserial_mbed/examples directory, and open the Buzzer.cpp file in your favorite text editor:

   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 off of:
   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     buzzer.write(0.0);
  32     led = 1;
  33     playing = false;
  34 }
  35 void beep(float freq, float time) {
  36     buzzer.period(1.0/freq);
  37     buzzer.write(0.5);
  38     toff.attach(nobeep, time);
  39     led = 0;
  40 }
  41 
  42 void messageCb(const std_msgs::Float32MultiArray& msg){
  43     if(!playing){
  44         playing = true;
  45         // msg.data[0] - Note
  46         // msg.data[1] - duration in seconds
  47         beep(msg.data[0], msg.data[1]);
  48     }
  49 }
  50 
  51 ros::Subscriber<std_msgs::Float32MultiArray> sub("buzzer", &messageCb);
  52 
  53 int main() {
  54     buzzer = 0;
  55     led = 1;
  56     nh.initNode();
  57     nh.subscribe(sub);
  58     while (1) {
  59         nh.spinOnce();
  60         wait_ms(1);
  61     }
  62 }

Compiling and uploading the Code

As seen on the previous tutorial, you must compile the source code by using the makefile in order to generate the .bin file that will be uploaded later to your MBED board. This is no different from uploading any other mbed binary.

Launching the App

Launch roscore

roscore

Run the serial node with the right serial port corresponding to your MBED board

$ rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0

$ rosrun rosserial_python serial_node.py /dev/ttyUSB0

Finally, you must publish the pitches by following this Reference pitches and duration (in seconds).

$ rostopic pub /buzzer std_msgs/Float32MultiArray "{46, 2}"

Wiki: rosserial_mbed/Tutorials/Buzzer Module (last edited 2016-01-04 20:00:00 by AlexisPojomovsky)