This program is porting rosserial_arduino for mbed http://www.ros.org/wiki/rosserial_arduino This program supported the revision of 169 of rosserial. This program contains an example.

Dependencies:   rosserial_mbed_lib mbed Servo

Embed: (wiki syntax)

« Back to documentation index

Show/hide line numbers ADC.cpp Source File

ADC.cpp

00001 //#define COMPILE_ADC_CODE_ROSSERIAL
00002 #ifdef  COMPILE_ADC_CODE_ROSSERIAL
00003 
00004 /*
00005  * rosserial ADC Example
00006  *
00007  * This is a poor man's Oscilloscope.  It does not have the sampling
00008  * rate or accuracy of a commerical scope, but it is great to get
00009  * an analog value into ROS in a pinch.
00010  */
00011 
00012 #include "mbed.h"
00013 #include <ros.h>
00014 #include <rosserial_mbed/Adc.h>
00015 
00016 ros::NodeHandle nh;
00017 
00018 rosserial_mbed::Adc adc_msg;
00019 ros::Publisher p("adc", &adc_msg);
00020 
00021 
00022 
00023 //We average the analog reading to elminate some of the noise
00024 int averageAnalog(PinName pin) {
00025     int v=0;
00026     for (int i=0; i<4; i++) v+= AnalogIn(pin).read_u16();
00027     return v/4;
00028 }
00029 
00030 long adc_timer;
00031 
00032 int main() {
00033     nh.initNode();
00034 
00035     nh.advertise(p);
00036 
00037     while (1) {
00038         adc_msg.adc0 = averageAnalog(p15);
00039         adc_msg.adc1 = averageAnalog(p16);
00040         adc_msg.adc2 = averageAnalog(p17);
00041         adc_msg.adc3 = averageAnalog(p18);
00042         adc_msg.adc4 = averageAnalog(p19);
00043         adc_msg.adc5 = averageAnalog(p20);
00044 
00045         p.publish(&adc_msg);
00046 
00047         nh.spinOnce();
00048     }
00049 }
00050 
00051 #endif