capstone_finish
Dependencies: BufferedSerial motor_sn7544
main.cpp
- Committer:
- Jeonghoon
- Date:
- 2019-11-21
- Revision:
- 9:ccd662244071
- Parent:
- 8:221b2fc093e4
- Child:
- 10:ca4e4062701a
File content as of revision 9:ccd662244071:
// // 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/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); 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) ; #define NUMBYTE 480 //#undef QQVGA #define QQVGA #ifdef QQVGA # define SIZEX (160) # define SIZEY (120) #else # define SIZEX (320) # define SIZEY (240) #endif uint8_t fdata[SIZEX*SIZEY]; uint8_t fdata_ros[NUMBYTE]; int loop_num; size_t size = SIZEX*SIZEY; int main() { nh.initNode(); loop_num = size/NUMBYTE; 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() ; sync.data=true; for (int y = 0; y < SIZEX*SIZEY ; y++) { camera.ReadOneByte(); fdata[y]=camera.ReadOneByte(); } camera.ReadStop() ; 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 = NUMBYTE; img.data = &fdata_ros[0]; img_pub.publish(&img); nh.spinOnce(); sync.data=false; wait_us(3125); // 25000us 12500 } } }