complete ov7670

Dependencies:   BufferedSerial

Files at this revision

API Documentation at this revision

Comitter:
Jeonghoon
Date:
Thu Nov 21 10:36:11 2019 +0000
Parent:
8:221b2fc093e4
Commit message:
complete ov7670;

Changed in this revision

MbedHardware.h Show annotated file Show diff for this revision Revisions of this file
main.cpp Show annotated file Show diff for this revision Revisions of this file
mbed-os.lib Show annotated file Show diff for this revision Revisions of this file
--- a/MbedHardware.h	Fri Sep 06 02:09:38 2019 +0000
+++ b/MbedHardware.h	Thu Nov 21 10:36:11 2019 +0000
@@ -14,7 +14,7 @@
 
 class MbedHardware {
   public:
-    MbedHardware(PinName tx, PinName rx, long baud = 57600)
+    MbedHardware(PinName tx, PinName rx, long baud = 1843200)
       :iostream(tx, rx){
       baud_ = baud;
       t.start();
@@ -22,7 +22,7 @@
 
     MbedHardware()
       :iostream(USBTX, USBRX) {
-        baud_ = 57600;
+        baud_ = 1843200;
         t.start();
     }
 
--- a/main.cpp	Fri Sep 06 02:09:38 2019 +0000
+++ b/main.cpp	Thu Nov 21 10:36:11 2019 +0000
@@ -6,9 +6,11 @@
 #include <ros.h>
 #include <ros/time.h>
 #include <std_msgs/UInt8MultiArray.h>
+#include <std_msgs/Byte.h>
 #include <std_msgs/Bool.h>
 
 std_msgs::UInt8MultiArray img;
+//std_msgs::Byte img;
 std_msgs::Bool sync;
 ros::NodeHandle nh;
 ros::Publisher img_pub("image_data", &img);
@@ -25,6 +27,7 @@
 
 //Serial pc(USBTX,USBRX,115200) ;
 
+#define NUMBYTE 480
 
 //#undef QQVGA
 #define QQVGA
@@ -32,7 +35,7 @@
 #ifdef QQVGA
 # define SIZEX (160)
 # define SIZEY (120)
-# define NUMBYTE (2)
+
 #else
 # define SIZEX (320)
 # define SIZEY (240)
@@ -40,14 +43,17 @@
 
 
 uint8_t fdata[SIZEX*SIZEY];
-uint8_t fdata_ros[480];
-
+uint8_t fdata_ros[NUMBYTE];
+int loop_num;
 
 
 size_t size = SIZEX*SIZEY;
 
 int main()
-{   sync.data=true;
+{   
+    nh.initNode();
+    loop_num = size/NUMBYTE;
+    sync.data=true;
     wait_ms(1);
 //    pc.baud(115200) ;
     camera.Reset() ;
@@ -74,30 +80,32 @@
 
         camera.ReadStart() ;
         
-      
+        sync.data=true;
+        
         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];
+
+        for(int x=0; x< loop_num; x++) {
+            for(int y=0; y < NUMBYTE; y++) {
+                fdata_ros[y]=fdata[(NUMBYTE*(x))+y];
             }
+            
             sync_pub.publish(&sync);
-            img.data_length = 480;
+            img.data_length = NUMBYTE;
             img.data = &fdata_ros[0];
             img_pub.publish(&img);
             nh.spinOnce();
-            sync.data=false;
-            wait_ms(600); //max...
             
-       }
-
+            sync.data=false;
+            wait_us(3125); // 25000us 12500
+            
+        }
 
        
     }
--- a/mbed-os.lib	Fri Sep 06 02:09:38 2019 +0000
+++ b/mbed-os.lib	Thu Nov 21 10:36:11 2019 +0000
@@ -1,1 +1,1 @@
-https://github.com/ARMmbed/mbed-os/#51d55508e8400b60af467005646c4e2164738d48
+https://github.com/ARMmbed/mbed-os/#949cb49ab0a144da0e3b04b6af46db0cd2a20d75