video.hpp
Go to the documentation of this file.
00001 
00005 #ifndef _THERMALVIS_VIDEO_H_
00006 #define _THERMALVIS_VIDEO_H_
00007 
00008 #include "general_resources.hpp"
00009 #include "ros_resources.hpp"
00010 #include "ffmpeg_resources.hpp"
00011 
00012 // http://credentiality2.blogspot.com.au/2010/04/v4l2-example.html
00013 
00014 namespace enc = sensor_msgs::image_encodings;
00015 
00016 #define CODEC_TYPE_VIDEO AVMEDIA_TYPE_VIDEO
00017 #define CODEC_TYPE_AUDIO AVMEDIA_TYPE_AUDIO
00018 
00019 #define CLEAR(x) memset (&(x), 0, sizeof (x))
00020 
00022 typedef struct {
00023   int width;
00024   int height;
00025   int bytes_per_pixel;
00026   int image_size;
00027   char *image;
00028   int is_new;
00029 } usb_cam_camera_image_t;
00030 
00031 typedef enum {
00032   IO_METHOD_READ,
00033   IO_METHOD_MMAP,
00034   IO_METHOD_USERPTR,
00035 } usb_cam_io_method;
00036 
00037 typedef enum {
00038   PIXEL_FORMAT_YUYV,
00039   PIXEL_FORMAT_UYVY,
00040   PIXEL_FORMAT_MJPEG,
00041 } usb_cam_pixel_format;
00042 
00044 struct usb_buffer {
00045   void * start;
00046   size_t length;
00047 };
00048 
00050 class streamerSource {
00051 public:
00052         
00053         struct SwsContext *video_sws;
00054 
00055         //AVFormatContext *pFormatCtx;
00056         int i, videoStream;
00057         AVCodecContext *pCodecCtx;
00058         AVCodec *pCodec;
00059         AVFrame *pFrame;
00060         AVFrame *pFrameRGB;
00061         AVPacket packet;
00062         int frameFinished;
00063         int numBytes;
00064         uint8_t *buffer;
00065         uint8_t *videoBuffer;
00066 
00067         char *camera_dev;
00068         unsigned int pixelformat;
00069         
00070         usb_cam_io_method io;
00071         int fd;
00072         struct usb_buffer * buffers;
00073         unsigned int n_buffers;
00074         AVFrame *avframe_camera;
00075         AVFrame *avframe_rgb;
00076         AVCodec *avcodec;
00077         AVCodecContext *avcodec_context;
00078         int avframe_camera_size;
00079         int avframe_rgb_size;
00080         usb_cam_camera_image_t* image;
00081 
00082         // Portugese one:
00083         int bRet, ix;
00084         // Input
00085             //const char *sFile = "/dev/video0";
00086             AVFormatContext *pIFormatCtx;
00087             AVCodecContext *pICodecCtx;
00088             AVCodec *pICodec;
00089             //AVFrame *pFrame;
00090             int ixInputStream;
00091             AVInputFormat *pIFormat;
00092             AVPacket oPacket;
00093             int fFrame;
00094         // Output
00095             AVCodecContext *pOCodecCtx;
00096             AVCodec *pOCodec;
00097             //uint8_t *pBuffer;
00098             int szBuffer;
00099             int szBufferActual;
00100             int bImgFormat;
00101             int bQuality;
00102             FILE *fdJPEG;
00103 
00104         /*
00105         static usb_cam_io_method io = IO_METHOD_MMAP;
00106         static int fd = -1;
00107         struct buffer * buffers = NULL;
00108         static unsigned int n_buffers = 0;
00109         static AVFrame *avframe_camera = NULL;
00110         static AVFrame *avframe_rgb = NULL;
00111         static AVCodec *avcodec = NULL;
00112         static AVCodecContext *avcodec_context = NULL;
00113         static int avframe_camera_size = 0;
00114         static int avframe_rgb_size = 0;
00115         */
00116 
00117         // Generic functions
00118         void initialize_video_source();
00119 
00120         // File functions
00121         int setup_video_file(std::string filename);
00122 
00123         int close_video_file(std::string filename);
00124 
00125         // Capture functions
00126         int setup_video_capture(std::string devicename, int& deviceWidth, int& deviceHeight, bool verbose = false);
00127         void close_video_capture();
00128 
00129 
00130         void usb_cam_camera_start(const char* dev, usb_cam_io_method io, usb_cam_pixel_format pf, int width, int height);
00131         // shutdown camera
00132         void usb_cam_camera_shutdown(void);
00133         // grabs a new image from the camera
00134         void usb_cam_camera_grab_image();
00135 
00136         void open_device();
00137         void close_device();
00138         void init_device(int image_width, int image_height);
00139         void init_userp(unsigned int buffer_size);
00140         void init_mmap();
00141         void init_read(unsigned int buffer_size);
00142         void uninit_device();
00143         void start_capturing();
00144         void stop_capturing();
00145         int read_frame();
00146         void process_image(const void * src, int len, usb_cam_camera_image_t *dest);
00147         void mjpeg2rgb(char *MJPEG, int len, char *RGB, int NumPixels);
00148         int init_mjpeg_decoder(int image_width, int image_height);
00149         void yuyv2rgb(char *YUV, char *RGB, int NumPixels);
00150         void uyvy2rgb (char *YUV, char *RGB, int NumPixels);
00151 
00152         void YUV2RGB(const unsigned char y,
00153                 const unsigned char u,
00154                 const unsigned char v,
00155                 unsigned char* r,
00156                 unsigned char* g,
00157                 unsigned char* b);
00158 
00159         //unsigned char CLIPVALUE(int val);
00160 
00161         int xioctl(int fd, int request, void * arg);
00162         void errno_exit(const char * s);
00163 
00164 };
00165 
00166 #endif


thermalvis
Author(s): Stephen Vidas
autogenerated on Sun Jan 5 2014 11:38:45