usb_cam.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2014, Robert Bosch LLC.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the Robert Bosch nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  *********************************************************************/
00036 #ifndef USB_CAM_USB_CAM_H
00037 #define USB_CAM_USB_CAM_H
00038 
00039 #include <asm/types.h>          /* for videodev2.h */
00040 
00041 extern "C"
00042 {
00043 #include <linux/videodev2.h>
00044 #include <libavcodec/avcodec.h>
00045 #include <libswscale/swscale.h>
00046 #include <libavutil/mem.h>
00047 }
00048 
00049 // legacy reasons
00050 #include <libavcodec/version.h>
00051 #if LIBAVCODEC_VERSION_MAJOR < 55
00052 #define AV_CODEC_ID_MJPEG CODEC_ID_MJPEG
00053 #endif
00054 
00055 #include <string>
00056 #include <sstream>
00057 
00058 #include <sensor_msgs/Image.h>
00059 
00060 namespace usb_cam {
00061 
00062 class UsbCam {
00063  public:
00064   typedef enum
00065   {
00066     IO_METHOD_READ, IO_METHOD_MMAP, IO_METHOD_USERPTR, IO_METHOD_UNKNOWN,
00067   } io_method;
00068 
00069   typedef enum
00070   {
00071     PIXEL_FORMAT_YUYV, PIXEL_FORMAT_UYVY, PIXEL_FORMAT_MJPEG, PIXEL_FORMAT_YUVMONO10, PIXEL_FORMAT_RGB24, PIXEL_FORMAT_UNKNOWN
00072   } pixel_format;
00073 
00074   UsbCam();
00075   ~UsbCam();
00076 
00077   // start camera
00078   void start(const std::string& dev, io_method io, pixel_format pf,
00079                     int image_width, int image_height, int framerate);
00080   // shutdown camera
00081   void shutdown(void);
00082 
00083   // grabs a new image from the camera
00084   void grab_image(sensor_msgs::Image* image);
00085 
00086   // enables/disable auto focus
00087   void set_auto_focus(int value);
00088 
00089   // Set video device parameters
00090   void set_v4l_parameter(const std::string& param, int value);
00091   void set_v4l_parameter(const std::string& param, const std::string& value);
00092 
00093   static io_method io_method_from_string(const std::string& str);
00094   static pixel_format pixel_format_from_string(const std::string& str);
00095 
00096  private:
00097   typedef struct
00098   {
00099     int width;
00100     int height;
00101     int bytes_per_pixel;
00102     int image_size;
00103     char *image;
00104     int is_new;
00105   } camera_image_t;
00106 
00107   struct buffer
00108   {
00109     void * start;
00110     size_t length;
00111   };
00112 
00113 
00114   int init_mjpeg_decoder(int image_width, int image_height);
00115   void mjpeg2rgb(char *MJPEG, int len, char *RGB, int NumPixels);
00116   void process_image(const void * src, int len, camera_image_t *dest);
00117   int read_frame();
00118   void stop_capturing(void);
00119   void start_capturing(void);
00120   void uninit_device(void);
00121   void init_read(unsigned int buffer_size);
00122   void init_mmap(void);
00123   void init_userp(unsigned int buffer_size);
00124   void init_device(int image_width, int image_height, int framerate);
00125   void close_device(void);
00126   void open_device(void);
00127   void grab_image();
00128 
00129 
00130   std::string camera_dev_;
00131   unsigned int pixelformat_;
00132   bool monochrome_;
00133   io_method io_;
00134   int fd_;
00135   buffer * buffers_;
00136   unsigned int n_buffers_;
00137   AVFrame *avframe_camera_;
00138   AVFrame *avframe_rgb_;
00139   AVCodec *avcodec_;
00140   AVDictionary *avoptions_;
00141   AVCodecContext *avcodec_context_;
00142   int avframe_camera_size_;
00143   int avframe_rgb_size_;
00144   struct SwsContext *video_sws_;
00145   camera_image_t *image_;
00146 
00147 };
00148 
00149 }
00150 
00151 #endif
00152 


usb_cam
Author(s): Benjamin Pitzer
autogenerated on Wed Aug 26 2015 16:38:37