capstone_finish

Dependencies:   BufferedSerial motor_sn7544

Files at this revision

API Documentation at this revision

Comitter:
kangmingyo
Date:
Fri Sep 06 02:09:38 2019 +0000
Parent:
7:152fba230106
Child:
9:ccd662244071
Commit message:
final

Changed in this revision

main.cpp Show annotated file Show diff for this revision Revisions of this file
--- a/main.cpp	Thu Sep 05 13:04:01 2019 +0000
+++ b/main.cpp	Fri Sep 06 02:09:38 2019 +0000
@@ -6,10 +6,13 @@
 #include <ros.h>
 #include <ros/time.h>
 #include <std_msgs/UInt8MultiArray.h>
+#include <std_msgs/Bool.h>
 
 std_msgs::UInt8MultiArray img;
+std_msgs::Bool sync;
 ros::NodeHandle nh;
 ros::Publisher img_pub("image_data", &img);
+ros::Publisher sync_pub("sync", &sync);
 
 
 
@@ -39,16 +42,17 @@
 uint8_t fdata[SIZEX*SIZEY];
 uint8_t fdata_ros[480];
 
-uint8_t dummy;
+
 
 size_t size = SIZEX*SIZEY;
 
 int main()
-{
+{   sync.data=true;
     wait_ms(1);
 //    pc.baud(115200) ;
     camera.Reset() ;
     nh.advertise(img_pub);
+    nh.advertise(sync_pub);
 
 #ifdef QQVGA
 //    camera.InitQQVGA565(true,false) ;
@@ -61,7 +65,7 @@
 
     // CAPTURE and SEND LOOP
 
-
+    
     while(1) {
 
             
@@ -69,24 +73,29 @@
         while(camera.CaptureDone() == false) ;
 
         camera.ReadStart() ;
-
+        
+      
         for (int y = 0; y < SIZEX*SIZEY ; y++) {
             camera.ReadOneByte();
             fdata[y]=camera.ReadOneByte();
         }
-        
+       sync.data=true;
+       
+
         camera.ReadStop() ;
         
        for(int x=0; x<40; x++) {
             for(int y=0; y<480; y++) {
                 fdata_ros[y]=fdata[(480*(x))+y];
             }
-        
+            sync_pub.publish(&sync);
             img.data_length = 480;
             img.data = &fdata_ros[0];
             img_pub.publish(&img);
             nh.spinOnce();
+            sync.data=false;
             wait_ms(600); //max...
+            
        }