Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
Dependencies: Servo mbed rosserial_mbed_lib
Fork of rosserial_mbed by
examples/ADC.cpp
- Committer:
 - garyservin
 - Date:
 - 2014-05-01
 - Revision:
 - 5:e52b44294b2b
 - Parent:
 - 0:06fc856e99ca
 
File content as of revision 5:e52b44294b2b:
//#define COMPILE_ADC_CODE_ROSSERIAL
#ifdef  COMPILE_ADC_CODE_ROSSERIAL
/*
 * 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 "mbed.h"
#include <ros.h>
#include <rosserial_mbed/Adc.h>
ros::NodeHandle nh;
rosserial_mbed::Adc adc_msg;
ros::Publisher p("adc", &adc_msg);
//We average the analog reading to elminate some of the noise
int averageAnalog(PinName pin) {
    int v=0;
    for (int i=0; i<4; i++) v+= AnalogIn(pin).read_u16();
    return v/4;
}
long adc_timer;
int main() {
    nh.initNode();
    nh.advertise(p);
    while (1) {
        adc_msg.adc0 = averageAnalog(p15);
        adc_msg.adc1 = averageAnalog(p16);
        adc_msg.adc2 = averageAnalog(p17);
        adc_msg.adc3 = averageAnalog(p18);
        adc_msg.adc4 = averageAnalog(p19);
        adc_msg.adc5 = averageAnalog(p20);
        p.publish(&adc_msg);
        nh.spinOnce();
    }
}
#endif
            
    