ADC.cpp
Go to the documentation of this file.
00001 /*
00002  * rosserial ADC Example
00003  *
00004  * This is a poor man's Oscilloscope.  It does not have the sampling
00005  * rate or accuracy of a commerical scope, but it is great to get
00006  * an analog value into ROS in a pinch.
00007  */
00008 
00009 #include "mbed.h"
00010 #include <ros.h>
00011 #include <rosserial_mbed/Adc.h>
00012 
00013 #if defined(TARGET_LPC1768)
00014 PinName adc0 = p15;
00015 PinName adc1 = p16;
00016 PinName adc2 = p17;
00017 PinName adc3 = p18;
00018 PinName adc4 = p19;
00019 PinName adc5 = p20;
00020 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
00021 PinName adc0 = A0;
00022 PinName adc1 = A1;
00023 PinName adc2 = A2;
00024 PinName adc3 = A3;
00025 PinName adc4 = A4;
00026 PinName adc5 = A5;
00027 #else
00028 #error "You need to specify the pins for the adcs"
00029 #endif
00030 
00031 ros::NodeHandle nh;
00032 
00033 rosserial_mbed::Adc adc_msg;
00034 ros::Publisher p("adc", &adc_msg);
00035 
00036 
00037 //We average the analog reading to elminate some of the noise
00038 int averageAnalog(PinName pin) {
00039     int v=0;
00040     for (int i=0; i<4; i++) v+= AnalogIn(pin).read_u16();
00041     return v/4;
00042 }
00043 
00044 long adc_timer;
00045 
00046 int main() {
00047     nh.initNode();
00048 
00049     nh.advertise(p);
00050 
00051     while (1) {
00052         adc_msg.adc0 = averageAnalog(adc0);
00053         adc_msg.adc1 = averageAnalog(adc1);
00054         adc_msg.adc2 = averageAnalog(adc2);
00055         adc_msg.adc3 = averageAnalog(adc3);
00056         adc_msg.adc4 = averageAnalog(adc4);
00057         adc_msg.adc5 = averageAnalog(adc5);
00058 
00059         p.publish(&adc_msg);
00060 
00061         nh.spinOnce();
00062     }
00063 }
00064 


rosserial_mbed
Author(s): Gary Servin
autogenerated on Sat Oct 7 2017 03:08:46