capstone_finish
Dependencies: BufferedSerial motor_sn7544
Diff: main.cpp
- Revision:
- 7:152fba230106
- Parent:
- 6:fe8b32cb9357
- Child:
- 8:221b2fc093e4
--- a/main.cpp Tue Aug 13 07:51:37 2019 +0000 +++ b/main.cpp Thu Sep 05 13:04:01 2019 +0000 @@ -12,22 +12,24 @@ ros::Publisher img_pub("image_data", &img); + 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,0xFF, - D13,D12,D6) ; // RRST,OE,RCLK + PortB,0x00FF, + D13,D12,D6,D2) ; // RRST,OE,RCLK,WRST //Serial pc(USBTX,USBRX,115200) ; -Timer t; + //#undef QQVGA #define QQVGA #ifdef QQVGA -# define SIZEX (12) -# define SIZEY (8) +# define SIZEX (160) +# define SIZEY (120) +# define NUMBYTE (2) #else # define SIZEX (320) # define SIZEY (240) @@ -35,11 +37,15 @@ uint8_t fdata[SIZEX*SIZEY]; +uint8_t fdata_ros[480]; + +uint8_t dummy; size_t size = SIZEX*SIZEY; -int main() { - int last ; +int main() +{ + wait_ms(1); // pc.baud(115200) ; camera.Reset() ; nh.advertise(img_pub); @@ -48,43 +54,42 @@ // camera.InitQQVGA565(true,false) ; camera.InitQQVGAYUV(false,false); -#else +#else //camera.InitQVGA565(true,false) ; #endif - - + + // CAPTURE and SEND LOOP - t.start(); - last = t.read_ms() ; - - - while(1) - { - - img.data_length = size; - + + + while(1) { + + 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() ; + camera.ReadStop() ; + + for(int x=0; x<40; x++) { + for(int y=0; y<480; y++) { + fdata_ros[y]=fdata[(480*(x))+y]; + } - img.data = &fdata[0]; - img_pub.publish(&img); - + img.data_length = 480; + img.data = &fdata_ros[0]; + img_pub.publish(&img); + nh.spinOnce(); + wait_ms(600); //max... + } - nh.spinOnce(); - wait_ms(1); //max... + + } }