## page was renamed from rosserial_arduino_demos/Tutorials/Arduino Oscilloscope ## For instruction on writing tutorials ## http://www.ros.org/wiki/WritingTutorials #################################### ##FILL ME IN #################################### ## for a custom note with links: ## note = ## for the canned note of "This tutorial assumes that you have completed the previous tutorials:" just add the links ## note.0= ## descriptive title for the tutorial ## title = Arduino Oscilloscope ## multi-line description to be displayed in search ## description = In this tutorial, we will be making a poor man's oscilloscope using the Arduino's ADC (analog to digital converter) and rqt_plot. ## the next tutorial description (optional) ## next = ## links to next tutorial (optional) ## next.0.link=[[rosserial_arduino/Tutorials/NodeHandle and ArduinoHardware|NodeHandle and ArduinoHardware]] ## next.1.link= ## what level user is this tutorial for ## level= AdvancedCategory ## keywords = #################################### <> <> <> In this tutorial, we will be making a poor man's oscilloscope using the Arduino'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 Arduino'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. The code for this tutorial can be found in your Arduino IDE at File>Examples>ros_lib>ADC If you have not done so already, make sure to clone the rosserial stack and add it to your ROS_PACKAGE_PATH. == 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 Arduino. {{{ uint16 adc0 uint16 adc1 uint16 adc2 uint16 adc3 uint16 adc4 uint16 adc5 }}} This message is a part of the rosserial_arduino 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. {{{#!cplusplus block=scope /* * rosserial ADC Example * * This is a poor man's Oscilloscope. It does not have the sampling * rate or accuracy of a commerical scope, but it is great to get * an analog value into ROS in a pinch. */ #include #include #include ros::NodeHandle nh; rosserial_arduino::Adc adc_msg; ros::Publisher p("adc", &adc_msg); void setup() { pinMode(13, OUTPUT); nh.initNode(); nh.advertise(p); } //We average the analog reading to eliminate some of the noise int averageAnalog(int pin){ int v=0; for(int i=0; i<4; i++) v+= analogRead(pin); return v/4; } long adc_timer; void loop() { adc_msg.adc0 = averageAnalog(0); adc_msg.adc1 = averageAnalog(1); adc_msg.adc2 = averageAnalog(2); adc_msg.adc3 = averageAnalog(3); adc_msg.adc4 = averageAnalog(4); adc_msg.adc5 = averageAnalog(5); p.publish(&adc_msg); nh.spinOnce(); } }}} == Running the Oscilloscope == {{{ roscore }}} {{{{{{#!wiki version hydro indigo {{{ rosrun rosserial_python serial_node.py _port:=/dev/ttyUSB0 }}} }}}}}} {{{{{{#!wiki version groovy {{{ rosrun rosserial_python serial_node.py /dev/ttyUSB0 }}} }}}}}} {{{ rqt_plot adc/adc0 }}} Now, you should see the raw analog value on adc0 displayed in [[rqt_plot]]. The reported readings are going to be from 0-1024 because the Arduino has a 10-bit ADC. In order to get the actual voltage, adc_val / 1024 * Arduino supply voltage. Try connecting ADC0 to ground, 5V, and 3.3V on your arduino 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. {{attachment:RXPlot.jpg}} ## AUTOGENERATED DO NOT DELETE ## TutorialCategory ## FILL IN THE STACK TUTORIAL CATEGORY HERE