IrRanger.cpp
Go to the documentation of this file.
00001 /*
00002  * rosserial IR Ranger Example
00003  *
00004  * This example is calibrated for the Sharp GP2D120XJ00F.
00005  */
00006 
00007 #include <ros.h>
00008 #include <ros/time.h>
00009 #include <sensor_msgs/Range.h>
00010 
00011 ros::NodeHandle  nh;
00012 
00013 
00014 sensor_msgs::Range range_msg;
00015 ros::Publisher pub_range( "range_data", &range_msg);
00016 
00017 #if defined(TARGET_LPC1768)
00018 PinName analog_pin = p20;
00019 #elif defined(TARGET_KL25Z) || defined(TARGET_NUCLEO_F401RE)
00020 PinName analog_pin = A0;
00021 #else
00022 #error "You need to specify a pin for the mic"
00023 #endif
00024 unsigned long range_timer;
00025 
00026 /*
00027  * getRange() - samples the analog input from the ranger
00028  * and converts it into meters.
00029  */
00030 float getRange(PinName pin_num) {
00031     int sample;
00032     // Get data
00033     sample = AnalogIn(pin_num).read_u16()/4;
00034     // if the ADC reading is too low,
00035     //   then we are really far away from anything
00036     if(sample < 10)
00037         return 254;     // max range
00038     // Magic numbers to get cm
00039     sample= 1309/(sample-3);
00040     return (sample - 1)/100; //convert to meters
00041 }
00042 
00043 char frameid[] = "/ir_ranger";
00044 
00045 Timer t;
00046 int main() {
00047     t.start();
00048     nh.initNode();
00049     nh.advertise(pub_range);
00050 
00051     range_msg.radiation_type = sensor_msgs::Range::INFRARED;
00052     range_msg.header.frame_id =  frameid;
00053     range_msg.field_of_view = 0.01;
00054     range_msg.min_range = 0.03;
00055     range_msg.max_range = 0.4;
00056 
00057     while (1) {
00058         // publish the range value every 50 milliseconds
00059         //   since it takes that long for the sensor to stabilize
00060         if ( (t.read_ms()-range_timer) > 50) {
00061             range_msg.range = getRange(analog_pin);
00062             range_msg.header.stamp = nh.now();
00063             pub_range.publish(&range_msg);
00064             range_timer =  t.read_ms() + 50;
00065         }
00066         nh.spinOnce();
00067     }
00068 }
00069 


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