capstone_finish

Dependencies:   BufferedSerial motor_sn7544

main.cpp

Committer:
Jeonghoon
Date:
2019-08-13
Revision:
3:2a3664dc6634
Parent:
2:e98408458d2b
Child:
4:7b63cf3d205f

File content as of revision 3:2a3664dc6634:

//
// OV7670 + FIFO AL422B camera board test
//
#include "mbed.h"
#include "ov7670.h"
#include <ros.h>
#include <ros/time.h>
#include <std_msgs/UInt8MultiArray.h>

std_msgs::UInt8MultiArray img;
ros::NodeHandle nh;
ros::Publisher img_pub("image_data", &img);


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

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

//#undef QQVGA
#define QQVGA

#ifdef QQVGA
# define SIZEX (12)
# define SIZEY (8)
#else
# define SIZEX (320)
# define SIZEY (240)
#endif


uint8_t fdata[SIZEX*SIZEY];

size_t size = SIZEX*SIZEY;

int main() {
    int last ;
//    pc.baud(115200) ;
    camera.Reset() ;
    nh.advertise(img_pub);

#ifdef QQVGA
//    camera.InitQQVGA565(true,false) ;
    camera.InitQVGAYUV(false,false);

#else 
    //camera.InitQVGA565(true,false) ;
#endif
    
    
    // CAPTURE and SEND LOOP
    t.start();
    last = t.read_ms() ;
    
    
    while(1)
    {
        
        img.data_length = size;
        
        camera.CaptureNext() ;
        while(camera.CaptureDone() == false) ;

        last = t.read_ms() ;
        camera.ReadStart() ;
        
        
        for (int y = 0; y < SIZEX*SIZEY ; y++) {
                
            camera.ReadOneByte();
            fdata[y]=camera.ReadOneByte();

        }
        
        camera.ReadStop() ; 
        last = t.read_ms() ;
        
        img.data = &fdata[0]; 
        img_pub.publish(&img);
        

        nh.spinOnce();
        wait_ms(1); //max...
    }
}