ros_serial for mbed updated to work with ROS Hydro. Library still needs to be debugged
Library and program still under development!
examples/ADC.cpp@0:cb1dffdc7d05, 2015-02-15 (annotated)
- Committer:
- akashvibhute
- Date:
- Sun Feb 15 10:54:04 2015 +0000
- Revision:
- 0:cb1dffdc7d05
Error: ; "mbed::Stream::Stream(const mbed::Stream &)" (declared at <a href="#" onmousedown="mbed_doc_goto('/mbed_roshydro_test//extras/mbed_e188a91d3eaa/Stream.h', '59'); return false;">/extras/mbed_e188a91d3eaa/Stream.h:59</a>) is inaccessible in "ext
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
akashvibhute | 0:cb1dffdc7d05 | 1 | //#define COMPILE_ADC_CODE_ROSSERIAL |
akashvibhute | 0:cb1dffdc7d05 | 2 | #ifdef COMPILE_ADC_CODE_ROSSERIAL |
akashvibhute | 0:cb1dffdc7d05 | 3 | |
akashvibhute | 0:cb1dffdc7d05 | 4 | /* |
akashvibhute | 0:cb1dffdc7d05 | 5 | * rosserial ADC Example |
akashvibhute | 0:cb1dffdc7d05 | 6 | * |
akashvibhute | 0:cb1dffdc7d05 | 7 | * This is a poor man's Oscilloscope. It does not have the sampling |
akashvibhute | 0:cb1dffdc7d05 | 8 | * rate or accuracy of a commerical scope, but it is great to get |
akashvibhute | 0:cb1dffdc7d05 | 9 | * an analog value into ROS in a pinch. |
akashvibhute | 0:cb1dffdc7d05 | 10 | */ |
akashvibhute | 0:cb1dffdc7d05 | 11 | |
akashvibhute | 0:cb1dffdc7d05 | 12 | #include "mbed.h" |
akashvibhute | 0:cb1dffdc7d05 | 13 | #include <ros.h> |
akashvibhute | 0:cb1dffdc7d05 | 14 | #include <rosserial_mbed/Adc.h> |
akashvibhute | 0:cb1dffdc7d05 | 15 | |
akashvibhute | 0:cb1dffdc7d05 | 16 | ros::NodeHandle nh; |
akashvibhute | 0:cb1dffdc7d05 | 17 | |
akashvibhute | 0:cb1dffdc7d05 | 18 | rosserial_mbed::Adc adc_msg; |
akashvibhute | 0:cb1dffdc7d05 | 19 | ros::Publisher p("adc", &adc_msg); |
akashvibhute | 0:cb1dffdc7d05 | 20 | |
akashvibhute | 0:cb1dffdc7d05 | 21 | |
akashvibhute | 0:cb1dffdc7d05 | 22 | |
akashvibhute | 0:cb1dffdc7d05 | 23 | //We average the analog reading to elminate some of the noise |
akashvibhute | 0:cb1dffdc7d05 | 24 | int averageAnalog(PinName pin) { |
akashvibhute | 0:cb1dffdc7d05 | 25 | int v=0; |
akashvibhute | 0:cb1dffdc7d05 | 26 | for (int i=0; i<4; i++) v+= AnalogIn(pin).read_u16(); |
akashvibhute | 0:cb1dffdc7d05 | 27 | return v/4; |
akashvibhute | 0:cb1dffdc7d05 | 28 | } |
akashvibhute | 0:cb1dffdc7d05 | 29 | |
akashvibhute | 0:cb1dffdc7d05 | 30 | long adc_timer; |
akashvibhute | 0:cb1dffdc7d05 | 31 | |
akashvibhute | 0:cb1dffdc7d05 | 32 | int main() { |
akashvibhute | 0:cb1dffdc7d05 | 33 | nh.initNode(); |
akashvibhute | 0:cb1dffdc7d05 | 34 | |
akashvibhute | 0:cb1dffdc7d05 | 35 | nh.advertise(p); |
akashvibhute | 0:cb1dffdc7d05 | 36 | |
akashvibhute | 0:cb1dffdc7d05 | 37 | while (1) { |
akashvibhute | 0:cb1dffdc7d05 | 38 | adc_msg.adc0 = averageAnalog(p15); |
akashvibhute | 0:cb1dffdc7d05 | 39 | adc_msg.adc1 = averageAnalog(p16); |
akashvibhute | 0:cb1dffdc7d05 | 40 | adc_msg.adc2 = averageAnalog(p17); |
akashvibhute | 0:cb1dffdc7d05 | 41 | adc_msg.adc3 = averageAnalog(p18); |
akashvibhute | 0:cb1dffdc7d05 | 42 | adc_msg.adc4 = averageAnalog(p19); |
akashvibhute | 0:cb1dffdc7d05 | 43 | adc_msg.adc5 = averageAnalog(p20); |
akashvibhute | 0:cb1dffdc7d05 | 44 | |
akashvibhute | 0:cb1dffdc7d05 | 45 | p.publish(&adc_msg); |
akashvibhute | 0:cb1dffdc7d05 | 46 | |
akashvibhute | 0:cb1dffdc7d05 | 47 | nh.spinOnce(); |
akashvibhute | 0:cb1dffdc7d05 | 48 | } |
akashvibhute | 0:cb1dffdc7d05 | 49 | } |
akashvibhute | 0:cb1dffdc7d05 | 50 | |
akashvibhute | 0:cb1dffdc7d05 | 51 | #endif |