commit 47e26deedb4fe15ac5f77d29fe323441a05238a2
Author: Tom Mullins <tmullins@andrew.cmu.edu>
Date:   Fri Nov 9 14:43:13 2012 -0500

    BOM testing code in main.cpp works with rosserial

diff --git a/scout_avr/src/main.cpp b/scout_avr/src/main.cpp
index 7bc6a7f..ef6df38 100644
--- a/scout_avr/src/main.cpp
+++ b/scout_avr/src/main.cpp
@@ -2,8 +2,9 @@
 
 #include "ros.h"
 #include "bom.h"
-
+#include "range.h"
 #include <std_msgs/Int16.h>
+#include <util/delay.h>
 
 ros::Publisher *pbom_pub;
 
@@ -26,6 +27,8 @@ int main()
   pbom_pub = &bom_pub;
 
   nh.initNode();
+  range_init();
+  bom_init();
   nh.subscribe(test_in);
   nh.advertise(bom_pub);
 
@@ -37,8 +40,9 @@ int main()
       id = 0;
     }
     set_robot_id(id);
+
+    bom_send(id & 1);
     for (i = 0; i < 4; i++) {
-      bom_send(i);
       int msg = bom_get(i);
       if (msg != BOM_NO_DATA) {
         bom_msg.sender = bom_msg_get_robot_id(msg);
@@ -47,7 +51,9 @@ int main()
         bom_pub.publish(&bom_msg);
       }
     }
+
     nh.spinOnce();
+    _delay_ms(500);
   }
 
   return 0;
