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
examples/Ultrasound.cpp@0:06fc856e99ca, 2011-08-19 (annotated)
- Committer:
- nucho
- Date:
- Fri Aug 19 09:06:16 2011 +0000
- Revision:
- 0:06fc856e99ca
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
nucho | 0:06fc856e99ca | 1 | //#define COMPILE_ULTRASOUND_CODE_ROSSERIAL |
nucho | 0:06fc856e99ca | 2 | #ifdef COMPILE_ULTRASOUND_CODE_ROSSERIAL |
nucho | 0:06fc856e99ca | 3 | |
nucho | 0:06fc856e99ca | 4 | /* |
nucho | 0:06fc856e99ca | 5 | * rosserial Ultrasound Example |
nucho | 0:06fc856e99ca | 6 | * |
nucho | 0:06fc856e99ca | 7 | * This example is for the Maxbotix Ultrasound rangers. |
nucho | 0:06fc856e99ca | 8 | */ |
nucho | 0:06fc856e99ca | 9 | |
nucho | 0:06fc856e99ca | 10 | #include "mbed.h" |
nucho | 0:06fc856e99ca | 11 | #include <ros.h> |
nucho | 0:06fc856e99ca | 12 | #include <ros/time.h> |
nucho | 0:06fc856e99ca | 13 | #include <sensor_msgs/Range.h> |
nucho | 0:06fc856e99ca | 14 | |
nucho | 0:06fc856e99ca | 15 | ros::NodeHandle nh; |
nucho | 0:06fc856e99ca | 16 | |
nucho | 0:06fc856e99ca | 17 | sensor_msgs::Range range_msg; |
nucho | 0:06fc856e99ca | 18 | ros::Publisher pub_range( "/ultrasound", &range_msg); |
nucho | 0:06fc856e99ca | 19 | |
nucho | 0:06fc856e99ca | 20 | const PinName adc_pin = p20; |
nucho | 0:06fc856e99ca | 21 | |
nucho | 0:06fc856e99ca | 22 | char frameid[] = "/ultrasound"; |
nucho | 0:06fc856e99ca | 23 | |
nucho | 0:06fc856e99ca | 24 | float getRange_Ultrasound(PinName pin_num) { |
nucho | 0:06fc856e99ca | 25 | int val = 0; |
nucho | 0:06fc856e99ca | 26 | for (int i=0; i<4; i++) val += AnalogIn(pin_num).read_u16(); |
nucho | 0:06fc856e99ca | 27 | float range = val; |
nucho | 0:06fc856e99ca | 28 | return range /322.519685; // (0.0124023437 /4) ; //cvt to meters |
nucho | 0:06fc856e99ca | 29 | } |
nucho | 0:06fc856e99ca | 30 | |
nucho | 0:06fc856e99ca | 31 | Timer t; |
nucho | 0:06fc856e99ca | 32 | int main() { |
nucho | 0:06fc856e99ca | 33 | t.start(); |
nucho | 0:06fc856e99ca | 34 | nh.initNode(); |
nucho | 0:06fc856e99ca | 35 | nh.advertise(pub_range); |
nucho | 0:06fc856e99ca | 36 | |
nucho | 0:06fc856e99ca | 37 | range_msg.radiation_type = sensor_msgs::Range::ULTRASOUND; |
nucho | 0:06fc856e99ca | 38 | range_msg.header.frame_id = frameid; |
nucho | 0:06fc856e99ca | 39 | range_msg.field_of_view = 0.1; // fake |
nucho | 0:06fc856e99ca | 40 | range_msg.min_range = 0.0; |
nucho | 0:06fc856e99ca | 41 | range_msg.max_range = 6.47; |
nucho | 0:06fc856e99ca | 42 | |
nucho | 0:06fc856e99ca | 43 | //pinMode(8,OUTPUT); |
nucho | 0:06fc856e99ca | 44 | //digitalWrite(8, LOW); |
nucho | 0:06fc856e99ca | 45 | |
nucho | 0:06fc856e99ca | 46 | long range_time=0; |
nucho | 0:06fc856e99ca | 47 | |
nucho | 0:06fc856e99ca | 48 | while (1) { |
nucho | 0:06fc856e99ca | 49 | |
nucho | 0:06fc856e99ca | 50 | //publish the adc value every 50 milliseconds |
nucho | 0:06fc856e99ca | 51 | //since it takes that long for the sensor to stablize |
nucho | 0:06fc856e99ca | 52 | if ( t.read_ms() >= range_time ) { |
nucho | 0:06fc856e99ca | 53 | int r =0; |
nucho | 0:06fc856e99ca | 54 | |
nucho | 0:06fc856e99ca | 55 | range_msg.range = getRange_Ultrasound(adc_pin); |
nucho | 0:06fc856e99ca | 56 | range_msg.header.stamp = nh.now(); |
nucho | 0:06fc856e99ca | 57 | pub_range.publish(&range_msg); |
nucho | 0:06fc856e99ca | 58 | range_time = t.read_ms() + 50; |
nucho | 0:06fc856e99ca | 59 | } |
nucho | 0:06fc856e99ca | 60 | |
nucho | 0:06fc856e99ca | 61 | nh.spinOnce(); |
nucho | 0:06fc856e99ca | 62 | } |
nucho | 0:06fc856e99ca | 63 | } |
nucho | 0:06fc856e99ca | 64 | |
nucho | 0:06fc856e99ca | 65 | #endif |