al422b

Dependencies:   BufferedSerial

main.cpp

Committer:
kangmingyo
Date:
2019-09-06
Revision:
8:221b2fc093e4
Parent:
7:152fba230106

File content as of revision 8:221b2fc093e4:

//
// OV7670 + FIFO AL422B camera board test
//
#include "mbed.h"
#include "ov7670.h"
#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);



OV7670 camera(
    D14,D15,       // SDA,SCL(I2C / SCCB)
    D9,D8,D11,   // VSYNC,HREF,WEN(FIFO)
    //p18,p17,p16,p15,p11,p12,p14,p13, // D7-D0
    PortB,0x00FF,
    D13,D12,D6,D2) ; // RRST,OE,RCLK,WRST

//Serial pc(USBTX,USBRX,115200) ;


//#undef QQVGA
#define QQVGA

#ifdef QQVGA
# define SIZEX (160)
# define SIZEY (120)
# define NUMBYTE (2)
#else
# define SIZEX (320)
# define SIZEY (240)
#endif


uint8_t fdata[SIZEX*SIZEY];
uint8_t fdata_ros[480];



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) ;
    camera.InitQQVGAYUV(false,false);

#else
    //camera.InitQVGA565(true,false) ;
#endif


    // CAPTURE and SEND LOOP

    
    while(1) {

            
        camera.CaptureNext() ;
        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...
            
       }


       
    }
}