play.cpp
Go to the documentation of this file.
00001 #include <unistd.h>
00002 #include <cstdio>
00003 #include <cassert>
00004 #include <ros/time.h>
00005 #include "SDL/SDL.h"
00006 
00007 const unsigned WIDTH = 640, HEIGHT = 480;
00008 
00009 inline unsigned char saturate(float f)
00010 {
00011   return (unsigned char)( f >= 255 ? 255 : (f < 0 ? 0 : f));
00012 }
00013 
00014 int main(int argc, char **argv)
00015 {
00016   if (argc != 2)
00017   {
00018     fprintf(stderr, "usage: play FILE\n");
00019     return 1;
00020   }
00021 
00022   if (SDL_Init(SDL_INIT_VIDEO) < 0)
00023   {
00024     fprintf(stderr, "sdl init error: %s\n", SDL_GetError());
00025     return 1;
00026   }
00027   atexit(SDL_Quit);
00028   SDL_Surface *surf = SDL_SetVideoMode(WIDTH, HEIGHT, 24, SDL_HWSURFACE);
00029   assert(surf);
00030   SDL_WM_SetCaption("hello world", "hello world");
00031   ros::Time t_prev(ros::Time::now());
00032   int count = 0;
00033   uint8_t *bgr_frame = new uint8_t[WIDTH*HEIGHT*3];
00034   uint8_t *yuv_frame = new uint8_t[WIDTH*HEIGHT*3];
00035   FILE *f = fopen(argv[1],"r");
00036   if (!f)
00037   {
00038     fprintf(stderr, "couldn't open dump file\n");
00039     return 1;
00040   }
00041   for (bool done = false; !done && !feof(f);)
00042   {
00043     double t;
00044     if (1 != fread(&t, sizeof(double), 1, f))
00045       break;
00046     printf("frame time: %15f\n", t);
00047     if (1 != fread(yuv_frame, WIDTH*HEIGHT*2, 1, f))
00048       break;
00049     uint8_t *prgb = bgr_frame;
00050     uint8_t *pyuv = yuv_frame;
00051     for (uint32_t i = 0; i < WIDTH*HEIGHT*2; i += 4)
00052     {
00053       *prgb++ = saturate(pyuv[i]+1.772f  *(pyuv[i+1]-128));
00054       *prgb++ = saturate(pyuv[i]-0.34414f*(pyuv[i+1]-128)-0.71414f*(pyuv[i+3]-128));
00055       *prgb++ = saturate(pyuv[i]+1.402f  *(pyuv[i+3]-128));
00056 
00057       *prgb++ = saturate(pyuv[i+2]+1.772f*(pyuv[i+1]-128));
00058       *prgb++ = saturate(pyuv[i+2]-0.34414f*(pyuv[i+1]-128)-0.71414f*(pyuv[i+3]-128));
00059       *prgb++ = saturate(pyuv[i+2]+1.402f*(pyuv[i+3]-128));
00060     }
00061     memcpy(surf->pixels, bgr_frame, WIDTH*HEIGHT*3);
00062 
00063     if (count++ % 30 == 0)
00064     {
00065       ros::Time t(ros::Time::now());
00066       ros::Duration d(t - t_prev);
00067       printf("%.1f fps\n", 30.0 / d.toSec());
00068       t_prev = t;
00069     }
00070     //usleep(100000);
00071     SDL_UpdateRect(surf, 0, 0, WIDTH, HEIGHT);
00072     SDL_Event event;
00073     while (SDL_PollEvent(&event))
00074     {
00075       switch (event.type)
00076       {
00077         case SDL_KEYDOWN:
00078           switch(event.key.keysym.sym)
00079           {
00080             case SDLK_ESCAPE: done = true; break;
00081             default: break;
00082           }
00083           break;
00084         case SDL_QUIT:
00085           done = true;
00086           break;
00087       }
00088     }
00089   }
00090   delete[] bgr_frame;
00091   return 0;
00092 }
00093 


uvc_cam2
Author(s): Morgan Quigley, extended and maintained by Juergen Sturm
autogenerated on Mon Oct 6 2014 00:08:38