ADC.cpp
Go to the documentation of this file.
1 /*
2  * rosserial ADC Example
3  *
4  * This is a poor man's Oscilloscope. It does not have the sampling
5  * rate or accuracy of a commerical scope, but it is great to get
6  * an analog value into ROS in a pinch.
7  */
8 
9 #include "mbed.h"
10 #include <ros.h>
11 #include <rosserial_mbed/Adc.h>
12 
13 #if defined(TARGET_LPC1768)
14 PinName adc0 = p15;
15 PinName adc1 = p16;
16 PinName adc2 = p17;
17 PinName adc3 = p18;
18 PinName adc4 = p19;
19 PinName adc5 = p20;
20 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
21 PinName adc0 = A0;
22 PinName adc1 = A1;
23 PinName adc2 = A2;
24 PinName adc3 = A3;
25 PinName adc4 = A4;
26 PinName adc5 = A5;
27 #else
28 #error "You need to specify the pins for the adcs"
29 #endif
30 
32 
33 rosserial_mbed::Adc adc_msg;
34 ros::Publisher p("adc", &adc_msg);
35 
36 
37 //We average the analog reading to elminate some of the noise
38 int averageAnalog(PinName pin) {
39  int v=0;
40  for (int i=0; i<4; i++) v+= AnalogIn(pin).read_u16();
41  return v/4;
42 }
43 
44 long adc_timer;
45 
46 int main() {
47  nh.initNode();
48 
49  nh.advertise(p);
50 
51  while (1) {
52  adc_msg.adc0 = averageAnalog(adc0);
53  adc_msg.adc1 = averageAnalog(adc1);
54  adc_msg.adc2 = averageAnalog(adc2);
55  adc_msg.adc3 = averageAnalog(adc3);
56  adc_msg.adc4 = averageAnalog(adc4);
57  adc_msg.adc5 = averageAnalog(adc5);
58 
59  p.publish(&adc_msg);
60 
61  nh.spinOnce();
62  }
63 }
64 
rosserial_mbed::Adc adc_msg
Definition: ADC.cpp:33
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle nh
Definition: ADC.cpp:31
ros::Publisher p("adc",&adc_msg)
long adc_timer
Definition: ADC.cpp:44
int averageAnalog(PinName pin)
Definition: ADC.cpp:38
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int i
int main()
Definition: ADC.cpp:46


rosserial_mbed
Author(s): Gary Servin
autogenerated on Fri Jun 7 2019 22:02:48