added broadcaster for l.mouse

Dependencies:   QEI mbed ros_lib_kinetic

Fork of Mouse_ISR by SBD Digital Accelerator Robotics

Revision:
1:7ba9803d4e01
Parent:
0:1a95e3b1026a
Child:
2:47663f3fec3a
--- a/main.cpp	Mon Jul 16 18:35:30 2018 +0000
+++ b/main.cpp	Mon Jul 16 19:47:46 2018 +0000
@@ -2,30 +2,21 @@
 #include "QEI.h"
 #include "ros.h"
 #include "geometry_msgs/Quaternion.h"
-//#include "std_msgs/String.h"
 
 //PINA / PINB / INDEXPIN / PPR / ENCODING (X2 BY DEFAULT)
 QEI leftEncoder(D3, D12, NC, 378);
 QEI rightEncoder(D2, D13, NC, 378);
 
-Timer tL, tR; 
-
-//Serial pc(USBTX, USBRX); 
-
 ros::NodeHandle nh;
 geometry_msgs::Quaternion wheelMsg;
 ros::Publisher wheelPub("/odom_msg", &wheelMsg); 
 
-//std_msgs::String str_msg; 
-//ros::Publisher chatter("chatter", &str_msg);
-
-//char hello[13]="Hello World";
-
+//rosserial does not like volatile ints
 int leftPulseA=0; 
 int rightPulseA=0;
 
-unsigned long timeL =0 ; 
-unsigned long timeR=0; 
+//timeL; 
+//timeR; 
 
 int main(){
     
@@ -39,13 +30,13 @@
     
     leftPulseA=leftEncoder.getPulses();
     rightPulseA = rightEncoder.getPulses();
-    timeL = tL.read();
-    timeR = tL.read();
+    //timeL = tL.read();
+    //timeR = tL.read();
     
     wheelMsg.x= leftPulseA;
-    wheelMsg.y = timeL;;
+    wheelMsg.y = 0.0;//timeL;
     wheelMsg.z = rightPulseA;
-    wheelMsg.w = timeR;    
+    wheelMsg.w = 0.0;//timeR;    
     
     
     //pc.printf("Left pulses %i \n", leftPulseA);