(!) 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.

MBED Oscilloscope

Description: In this tutorial, we will be making a poor man's oscilloscope using the MBED's ADC (analog to digital converter) and rqt_plot.

Keywords: MBED, rosserial, serial, ADC

Tutorial Level: BEGINNER

  Show EOL distros: 

In this tutorial, we will be making a poor man's oscilloscope using the MBED's ADC (analog to digital converter) and rqt_plot. We will set up a publisher which will forward the analog values from each of the mbed's 6 ADC pins to ROS using rosserial. This will be a relatively bad oscilloscope (very low sampling frequency and resolution), but it will be perfect for many quick and dirty setups.

Custom Message

This code uses a custom message type, the ADC.msg. This message has uint16 field for each of the analog input pins on the standard mbed.

uint16 adc0
uint16 adc1
uint16 adc2
uint16 adc3
uint16 adc4
uint16 adc5

This message is a part of the rosserial_mbed package and has been added to your ros_lib library.

The Code

The code for this tutorial is fairly straight forward. The code registers a Adc msg publisher, initializes the node handle, and then tries to publish as many Adc messages as possible.

   1 /*
   2  * rosserial ADC Example
   3  *
   4  * This is a poor man's Oscilloscope.  It does not have the sampling
   5  * rate or accuracy of a commerical scope, but it is great to get
   6  * an analog value into ROS in a pinch.
   7  */
   8 
   9 #include "mbed.h"
  10 #include <ros.h>
  11 #include <rosserial_mbed/Adc.h>
  12 
  13 #if defined(TARGET_LPC1768)
  14 PinName adc0 = p15;
  15 PinName adc1 = p16;
  16 PinName adc2 = p17;
  17 PinName adc3 = p18;
  18 PinName adc4 = p19;
  19 PinName adc5 = p20;
  20 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
  21 PinName adc0 = A0;
  22 PinName adc1 = A1;
  23 PinName adc2 = A2;
  24 PinName adc3 = A3;
  25 PinName adc4 = A4;
  26 PinName adc5 = A5;
  27 #else
  28 #error "You need to specify the pins for the adcs"
  29 #endif
  30 
  31 ros::NodeHandle nh;
  32 
  33 rosserial_mbed::Adc adc_msg;
  34 ros::Publisher p("adc", &adc_msg);
  35 
  36 
  37 //We average the analog reading to elminate some of the noise
  38 int averageAnalog(PinName pin) {
  39     int v=0;
  40     for (int i=0; i<4; i++) v+= AnalogIn(pin).read_u16();
  41     return v/4;
  42 }
  43 
  44 long adc_timer;
  45 
  46 int main() {
  47     nh.initNode();
  48 
  49     nh.advertise(p);
  50 
  51     while (1) {
  52         adc_msg.adc0 = averageAnalog(adc0);
  53         adc_msg.adc1 = averageAnalog(adc1);
  54         adc_msg.adc2 = averageAnalog(adc2);
  55         adc_msg.adc3 = averageAnalog(adc3);
  56         adc_msg.adc4 = averageAnalog(adc4);
  57         adc_msg.adc5 = averageAnalog(adc5);
  58 
  59         p.publish(&adc_msg);
  60 
  61         nh.spinOnce();
  62     }
  63 }

Running the Oscilloscope

roscore

rosrun rosserial_python serial_node.py _port:=/dev/ttyACM0

rosrun rosserial_python serial_node.py /dev/ttyACM0

rqt_plot adc/adc0

Now, you should see the raw analog value on adc0 displayed in rqt_plot. Try connecting ADC0 to ground, 5V, and 3.3V on your MBED and observing the value. Also notice that when you don't have anything connected to the ADC, it is a floating analog input and its value will oscillate randomly.

For example, look at the below output where the ADC0 input is switched between 5V and gnd. There are wild oscillations during the transition.

RXPlot.jpg

Wiki: rosserial_mbed/Tutorials/MBED Oscilloscope (last edited 2015-11-23 15:00:48 by AlexisPojomovsky)