uvc_cam.cpp
Go to the documentation of this file.
00001 /* This file is from the uvc_cam package by Morgan Quigley */
00002 #include <cstring>
00003 #include <string>
00004 #include <cstdio>
00005 #include <stdexcept>
00006 #include <dirent.h>
00007 #include <sys/stat.h>
00008 #include <sys/ioctl.h>
00009 #include <sys/mman.h>
00010 #include <fcntl.h>
00011 #include <errno.h>
00012 #include "uvc_cam/uvc_cam.h"
00013 #include "uvc_cam/ccvt.h"
00014 
00015 using std::string;
00016 using namespace uvc_cam;
00017 
00018 Cam::Cam(const char *_device, mode_t _mode, int _width, int _height, int _fps)
00019 : mode(_mode), device(_device),
00020   motion_threshold_luminance(100), motion_threshold_count(-1),
00021   width(_width), height(_height), fps(_fps), rgb_frame(NULL)
00022 {
00023   printf("opening %s\n", _device);
00024   if ((fd = open(_device, O_RDWR)) == -1)
00025     throw std::runtime_error("couldn't open " + device);
00026   memset(&fmt, 0, sizeof(v4l2_format));
00027   memset(&cap, 0, sizeof(v4l2_capability));
00028   if (ioctl(fd, VIDIOC_QUERYCAP, &cap) < 0)
00029     throw std::runtime_error("couldn't query " + device);
00030   if (!(cap.capabilities & V4L2_CAP_VIDEO_CAPTURE))
00031     throw std::runtime_error(device + " does not support capture");
00032   if (!(cap.capabilities & V4L2_CAP_STREAMING))
00033     throw std::runtime_error(device + " does not support streaming");
00034   // enumerate formats
00035   v4l2_fmtdesc f;
00036   memset(&f, 0, sizeof(f));
00037   f.index = 0;
00038   f.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00039   int ret;
00040   while ((ret = ioctl(fd, VIDIOC_ENUM_FMT, &f)) == 0)
00041   {
00042     printf("pixfmt %d = '%4s' desc = '%s'\n",
00043            f.index++, (char *)&f.pixelformat, f.description);
00044     // enumerate frame sizes
00045     v4l2_frmsizeenum fsize;
00046     fsize.index = 0;
00047     fsize.pixel_format = f.pixelformat;
00048     while ((ret = ioctl(fd, VIDIOC_ENUM_FRAMESIZES, &fsize)) == 0)
00049     {
00050       fsize.index++;
00051       if (fsize.type == V4L2_FRMSIZE_TYPE_DISCRETE)
00052       {
00053         printf("  discrete: %ux%u:   ",
00054                fsize.discrete.width, fsize.discrete.height);
00055         // enumerate frame rates
00056         v4l2_frmivalenum fival;
00057         fival.index = 0;
00058         fival.pixel_format = f.pixelformat;
00059         fival.width = fsize.discrete.width;
00060         fival.height = fsize.discrete.height;
00061         while ((ret = ioctl(fd, VIDIOC_ENUM_FRAMEINTERVALS, &fival)) == 0)
00062         {
00063           fival.index++;
00064           if (fival.type == V4L2_FRMIVAL_TYPE_DISCRETE)
00065           {
00066             printf("%u/%u ",
00067                    fival.discrete.numerator, fival.discrete.denominator);
00068           }
00069           else
00070             printf("I only handle discrete frame intervals...\n");
00071         }
00072         printf("\n");
00073       }
00074       else if (fsize.type == V4L2_FRMSIZE_TYPE_CONTINUOUS)
00075       {
00076         printf("  continuous: %ux%u to %ux%u\n",
00077                fsize.stepwise.min_width, fsize.stepwise.min_height,
00078                fsize.stepwise.max_width, fsize.stepwise.max_height);
00079       }
00080       else if (fsize.type == V4L2_FRMSIZE_TYPE_STEPWISE)
00081       {
00082         printf("  stepwise: %ux%u to %ux%u step %ux%u\n",
00083                fsize.stepwise.min_width,  fsize.stepwise.min_height,
00084                fsize.stepwise.max_width,  fsize.stepwise.max_height,
00085                fsize.stepwise.step_width, fsize.stepwise.step_height);
00086       }
00087       else
00088       {
00089         printf("  fsize.type not supported: %d\n", fsize.type);
00090       }
00091     }
00092   }
00093   if (errno != EINVAL)
00094     throw std::runtime_error("error enumerating frame formats");
00095   fmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00096   fmt.fmt.pix.width = width;
00097   fmt.fmt.pix.height = height;
00098   if (mode == MODE_RGB || mode == MODE_YUYV) // we'll convert later
00099     fmt.fmt.pix.pixelformat = V4L2_PIX_FMT_YUV420;
00100   else
00101     fmt.fmt.pix.pixelformat = V4L2_PIX_FMT_MJPEG;
00102   fmt.fmt.pix.field = V4L2_FIELD_ANY;
00103   if ((ret = ioctl(fd, VIDIOC_S_FMT, &fmt)) < 0)
00104     throw std::runtime_error("couldn't set format");
00105   if (fmt.fmt.pix.width != width || fmt.fmt.pix.height != height)
00106     throw std::runtime_error("pixel format unavailable");
00107   streamparm.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00108   streamparm.parm.capture.timeperframe.numerator = 1;
00109   streamparm.parm.capture.timeperframe.denominator = fps;
00110   if ((ret = ioctl(fd, VIDIOC_S_PARM, &streamparm)) < 0)
00111     printf("unable to set framerate");
00112   v4l2_queryctrl queryctrl;
00113   memset(&queryctrl, 0, sizeof(queryctrl));
00114   uint32_t i = V4L2_CID_BASE;
00115   while (i != V4L2_CID_LAST_EXTCTR)
00116   {
00117     queryctrl.id = i;
00118     if ((ret = ioctl(fd, VIDIOC_QUERYCTRL, &queryctrl)) == 0 &&
00119         !(queryctrl.flags & V4L2_CTRL_FLAG_DISABLED))
00120     {
00121       const char *ctrl_type = NULL;
00122       if (queryctrl.type == V4L2_CTRL_TYPE_INTEGER)
00123         ctrl_type = "int";
00124       else if (queryctrl.type == V4L2_CTRL_TYPE_BOOLEAN)
00125         ctrl_type = "bool";
00126       else if (queryctrl.type == V4L2_CTRL_TYPE_BUTTON)
00127         ctrl_type = "button";
00128       else if (queryctrl.type == V4L2_CTRL_TYPE_MENU)
00129         ctrl_type = "menu";
00130       printf("  %s (%s, %d, id = %x): %d to %d (%d)\n",
00131              ctrl_type,
00132              queryctrl.name, queryctrl.flags, queryctrl.id,
00133              queryctrl.minimum, queryctrl.maximum, queryctrl.step);
00134       if (queryctrl.type == V4L2_CTRL_TYPE_MENU)
00135       {
00136         v4l2_querymenu querymenu;
00137         memset(&querymenu, 0, sizeof(querymenu));
00138         querymenu.id = queryctrl.id;
00139         querymenu.index = 0;
00140         while (ioctl(fd, VIDIOC_QUERYMENU, &querymenu) == 0)
00141         {
00142           printf("    %d: %s\n", querymenu.index, querymenu.name);
00143           querymenu.index++;
00144         }
00145       }
00146 
00147     }
00148     else if (errno != EINVAL)
00149       throw std::runtime_error("couldn't query control");
00150     i++;
00151     if (i == V4L2_CID_LAST_NEW)
00152       i = V4L2_CID_CAMERA_CLASS_BASE_NEW;
00153     else if (i == V4L2_CID_CAMERA_CLASS_LAST)
00154       i = V4L2_CID_PRIVATE_BASE_OLD;
00155     else if (i == V4L2_CID_PRIVATE_LAST)
00156       i = V4L2_CID_BASE_EXTCTR;
00157   }
00158 
00159   try
00160   {
00161     // the commented labels correspond to the controls in guvcview and uvcdynctrl
00162 
00163     //set_control(V4L2_CID_EXPOSURE_AUTO_NEW, 2);
00164     set_control(10094851, 1); // Exposure, Auto Priority
00165     set_control(10094849, 1); // Exposure, Auto
00166     //set_control(168062321, 0); //Disable video processing
00167     //set_control(0x9a9010, 100);
00168     //set_control(V4L2_CID_EXPOSURE_ABSOLUTE_NEW, 300);
00169     //set_control(V4L2_CID_BRIGHTNESS, 140);
00170     //set_control(V4L2_CID_CONTRAST, 40);
00171     //set_control(V4L2_CID_WHITE_BALANCE_TEMP_AUTO_OLD, 0);
00172     set_control(9963776, 128); //Brightness
00173     set_control(9963777, 32); //Contrast
00174     set_control(9963788, 1); // White Balance Temperature, Auto
00175     set_control(9963802, 5984); // White Balance Temperature
00176     set_control(9963800, 2);  // power line frequency to 60 hz
00177     set_control(9963795, 200); // Gain
00178     set_control(9963803, 224); // Sharpness
00179     set_control(9963804, 1); //Backlight Compensation
00180     set_control(10094850, 250); // Exposure (Absolute)
00181     set_control(168062212, 16); //Focus (absolute)
00182     set_control(168062213, 3); //LED1 Mode
00183     set_control(168062214, 0); //LED1 Frequency
00184     set_control(9963778, 32); // Saturation
00185   }
00186   catch (std::runtime_error &ex)
00187   {
00188     printf("ERROR: could not set some settings.  \n %s \n", ex.what());
00189   }
00190 
00191 /*
00192   v4l2_jpegcompression v4l2_jpeg;
00193   if (ioctl(fd, VIDIOC_G_JPEGCOMP, &v4l2_jpeg) < 0)
00194     throw std::runtime_error("no jpeg compression iface exposed");
00195   printf("jpeg quality: %d\n", v4l2_jpeg.quality);
00196 */
00197 
00198   memset(&rb, 0, sizeof(rb));
00199   rb.count = NUM_BUFFER;
00200   rb.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00201   rb.memory = V4L2_MEMORY_MMAP;
00202   if (ioctl(fd, VIDIOC_REQBUFS, &rb) < 0)
00203     throw std::runtime_error("unable to allocate buffers");
00204   for (unsigned i = 0; i < NUM_BUFFER; i++)
00205   {
00206     memset(&buf, 0, sizeof(buf));
00207     buf.index = i;
00208     buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00209     buf.flags = V4L2_BUF_FLAG_TIMECODE;
00210     buf.timecode = timecode;
00211     buf.timestamp.tv_sec = 0;
00212     buf.timestamp.tv_usec = 0;
00213     buf.memory = V4L2_MEMORY_MMAP;
00214     if (ioctl(fd, VIDIOC_QUERYBUF, &buf) < 0)
00215       throw std::runtime_error("unable to query buffer");
00216     if (buf.length <= 0)
00217       throw std::runtime_error("buffer length is bogus");
00218     mem[i] = mmap(0, buf.length, PROT_READ, MAP_SHARED, fd, buf.m.offset);
00219     //printf("buf length = %d at %x\n", buf.length, mem[i]);
00220     if (mem[i] == MAP_FAILED)
00221       throw std::runtime_error("couldn't map buffer");
00222   }
00223   buf_length = buf.length;
00224   for (unsigned i = 0; i < NUM_BUFFER; i++)
00225   {
00226     memset(&buf, 0, sizeof(buf));
00227     buf.index = i;
00228     buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00229     buf.flags = V4L2_BUF_FLAG_TIMECODE;
00230     buf.timecode = timecode;
00231     buf.timestamp.tv_sec = 0;
00232     buf.timestamp.tv_usec = 0;
00233     buf.memory = V4L2_MEMORY_MMAP;
00234     if (ioctl(fd, VIDIOC_QBUF, &buf) < 0)
00235       throw std::runtime_error("unable to queue buffer");
00236   }
00237   int type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00238   if (ioctl(fd, VIDIOC_STREAMON, &type) < 0)
00239     throw std::runtime_error("unable to start capture");
00240   rgb_frame = new unsigned char[width * height * 3];
00241   last_yuv_frame = new unsigned char[width * height * 2];
00242 }
00243 
00244 Cam::~Cam()
00245 {
00246   // stop stream
00247   int type = V4L2_BUF_TYPE_VIDEO_CAPTURE, ret;
00248   if ((ret = ioctl(fd, VIDIOC_STREAMOFF, &type)) < 0)
00249     perror("VIDIOC_STREAMOFF");
00250   for (unsigned i = 0; i < NUM_BUFFER; i++)
00251     if (munmap(mem[i], buf_length) < 0)
00252       perror("failed to unmap buffer");
00253   close(fd);
00254   if (rgb_frame)
00255   {
00256     delete[] rgb_frame;
00257     delete[] last_yuv_frame;
00258   }
00259   last_yuv_frame = rgb_frame = NULL;
00260 }
00261 
00262 void Cam::enumerate()
00263 {
00264   string v4l_path = "/sys/class/video4linux";
00265   DIR *d = opendir(v4l_path.c_str());
00266   if (!d)
00267     throw std::runtime_error("couldn't open " + v4l_path);
00268   struct dirent *ent, *ent2, *ent3;
00269   int fd, ret;
00270   struct v4l2_capability v4l2_cap;
00271   while ((ent = readdir(d)) != NULL)
00272   {
00273     if (strncmp(ent->d_name, "video", 5))
00274       continue; // ignore anything not starting with "video"
00275     string dev_name = string("/dev/") + string(ent->d_name);
00276     printf("enumerating %s ...\n", dev_name.c_str());
00277     if ((fd = open(dev_name.c_str(), O_RDWR)) == -1)
00278       throw std::runtime_error("couldn't open " + dev_name + "  perhaps the " +
00279                                "permissions are not set correctly?");
00280     if ((ret = ioctl(fd, VIDIOC_QUERYCAP, &v4l2_cap)) < 0)
00281       throw std::runtime_error("couldn't query " + dev_name);
00282     printf("name = [%s]\n", v4l2_cap.card);
00283     printf("driver = [%s]\n", v4l2_cap.driver);
00284     printf("location = [%s]\n", v4l2_cap.bus_info);
00285     close(fd);
00286     string v4l_dev_path = v4l_path + string("/") + string(ent->d_name) +
00287                           string("/device");
00288     // my kernel is using /sys/class/video4linux/videoN/device/inputX/id
00289     DIR *d2 = opendir(v4l_dev_path.c_str());
00290     if (!d2)
00291       throw std::runtime_error("couldn't open " + v4l_dev_path);
00292     string input_dir;
00293     while ((ent2 = readdir(d2)) != NULL)
00294     {
00295       if (strncmp(ent2->d_name, "input", 5))
00296         continue; // ignore anything not beginning with "input"
00297 
00298       DIR *input = opendir((v4l_dev_path + string("/") + string(ent2->d_name)).c_str());
00299       bool output_set = false;
00300       while ((ent3 = readdir(input)) != NULL)
00301       {
00302         if (!strncmp(ent3->d_name, "input", 5))
00303         {
00304           input_dir = (string("input/") + string(ent3->d_name )).c_str();
00305           output_set = true;
00306           break;
00307         }
00308       }
00309       if (!output_set)
00310         input_dir = ent2->d_name;
00311       break;
00312     }
00313     closedir(d2);
00314     if (!input_dir.length())
00315       throw std::runtime_error("couldn't find input dir in " + v4l_dev_path);
00316     string vid_fname = v4l_dev_path + string("/") + input_dir +
00317                        string("/id/vendor");
00318     string pid_fname = v4l_dev_path + string("/") + input_dir +
00319                        string("/id/product");
00320     string ver_fname = v4l_dev_path + string("/") + input_dir +
00321                        string("/id/version");
00322     char vid[5], pid[5], ver[5];
00323     FILE *vid_fp = fopen(vid_fname.c_str(), "r");
00324     if (!vid_fp)
00325       throw std::runtime_error("couldn't open " + vid_fname);
00326     if (!fgets(vid, sizeof(vid), vid_fp))
00327       throw std::runtime_error("couldn't read VID from " + vid_fname);
00328     fclose(vid_fp);
00329     vid[4] = 0;
00330     printf("vid = [%s]\n", vid);
00331     FILE *pid_fp = fopen(pid_fname.c_str(), "r");
00332     if (!pid_fp)
00333       throw std::runtime_error("couldn't open " + pid_fname);
00334     if (!fgets(pid, sizeof(pid), pid_fp))
00335       throw std::runtime_error("couldn't read PID from " + pid_fname);
00336     fclose(pid_fp);
00337     printf("pid = [%s]\n", pid);
00338     FILE *ver_fp = fopen(ver_fname.c_str(), "r");
00339     if (!ver_fp)
00340       throw std::runtime_error("couldn't open " + ver_fname);
00341     if (!fgets(ver, sizeof(ver), ver_fp))
00342       throw std::runtime_error("couldn't read version from " + ver_fname);
00343     fclose(ver_fp);
00344     printf("ver = [%s]\n", ver);
00345   }
00346   closedir(d);
00347 }
00348 
00349 // saturate input into [0, 255]
00350 inline unsigned char sat(float f)
00351 {
00352   return (unsigned char)( f >= 255 ? 255 : (f < 0 ? 0 : f));
00353 }
00354 
00355 int Cam::grab(unsigned char **frame, uint32_t &bytes_used)
00356 {
00357   *frame = NULL;
00358   int ret = 0;
00359   fd_set rdset;
00360   timeval timeout;
00361   FD_ZERO(&rdset);
00362   FD_SET(fd, &rdset);
00363   timeout.tv_sec = 1;
00364   timeout.tv_usec = 0;
00365   bytes_used = 0;
00366   ret = select(fd + 1, &rdset, NULL, NULL, &timeout);
00367   if (ret == 0)
00368   {
00369     printf("select timeout in grab\n");
00370     return -1;
00371   }
00372   else if (ret < 0)
00373   {
00374     perror("couldn't grab image");
00375     return -1;
00376   }
00377   if (!FD_ISSET(fd, &rdset))
00378     return -1;
00379   memset(&buf, 0, sizeof(buf));
00380   buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00381   buf.memory = V4L2_MEMORY_MMAP;
00382   if (ioctl(fd, VIDIOC_DQBUF, &buf) < 0)
00383     throw std::runtime_error("couldn't dequeue buffer");
00384   bytes_used = buf.bytesused;
00385   if (mode == MODE_RGB)
00386   {
00387     int num_pixels_different = 0; // just look at the Y channel
00388     unsigned char *pyuv = (unsigned char *)mem[buf.index];
00389     // yuyv is 2 bytes per pixel. step through every pixel pair.
00390     unsigned char *prgb = rgb_frame;
00391     unsigned char *pyuv_last = last_yuv_frame;
00392     ccvt_420p_rgb24(width, height, pyuv, prgb);
00393     /*for (unsigned i = 0; i < width * height * 2; i += 4)
00394     {
00395       *prgb++ = sat(pyuv[i]+1.402f  *(pyuv[i+3]-128));
00396       *prgb++ = sat(pyuv[i]-0.34414f*(pyuv[i+1]-128)-0.71414f*(pyuv[i+3]-128));
00397       *prgb++ = sat(pyuv[i]+1.772f  *(pyuv[i+1]-128));
00398       *prgb++ = sat(pyuv[i+2]+1.402f*(pyuv[i+3]-128));
00399       *prgb++ = sat(pyuv[i+2]-0.34414f*(pyuv[i+1]-128)-0.71414f*(pyuv[i+3]-128));
00400       *prgb++ = sat(pyuv[i+2]+1.772f*(pyuv[i+1]-128));
00401       if ((int)pyuv[i] - (int)pyuv_last[i] > motion_threshold_luminance ||
00402           (int)pyuv_last[i] - (int)pyuv[i] > motion_threshold_luminance)
00403         num_pixels_different++;
00404       if ((int)pyuv[i+2] - (int)pyuv_last[i+2] > motion_threshold_luminance ||
00405           (int)pyuv_last[i+2] - (int)pyuv[i+2] > motion_threshold_luminance)
00406         num_pixels_different++;*/
00407 
00408       // this gives bgr images...
00409       /*
00410       *prgb++ = sat(pyuv[i]+1.772f  *(pyuv[i+1]-128));
00411       *prgb++ = sat(pyuv[i]-0.34414f*(pyuv[i+1]-128)-0.71414f*(pyuv[i+3]-128));
00412       *prgb++ = sat(pyuv[i]+1.402f  *(pyuv[i+3]-128));
00413       *prgb++ = sat(pyuv[i+2]+1.772f*(pyuv[i+1]-128));
00414       *prgb++ = sat(pyuv[i+2]-0.34414f*(pyuv[i+1]-128)-0.71414f*(pyuv[i+3]-128));
00415       *prgb++ = sat(pyuv[i+2]+1.402f*(pyuv[i+3]-128));
00416       */
00417     //}
00418     memcpy(last_yuv_frame, pyuv, width * height * 2);
00419     if (num_pixels_different > motion_threshold_count) // default: always true
00420       *frame = rgb_frame;
00421     else
00422     {
00423       *frame = NULL; // not enough luminance change
00424       release(buf.index); // let go of this image
00425     }
00426   }
00427   else if (mode == MODE_YUYV)
00428   {
00429     *frame = (uint8_t *)mem[buf.index];
00430   }
00431   else // mode == MODE_JPEG
00432   {
00433     //if (bytes_used > 100)
00434       *frame = (unsigned char *)mem[buf.index];
00435   }
00436   return buf.index;
00437 }
00438 
00439 void Cam::release(unsigned buf_idx)
00440 {
00441   if (buf_idx < NUM_BUFFER)
00442     if (ioctl(fd, VIDIOC_QBUF, &buf) < 0)
00443       throw std::runtime_error("couldn't requeue buffer");
00444 }
00445 
00446 void Cam::set_control(uint32_t id, int val)
00447 {
00448   v4l2_control c;
00449   c.id = id;
00450 
00451   if (ioctl(fd, VIDIOC_G_CTRL, &c) == 0)
00452   {
00453     printf("current value of %d is %d\n", id, c.value);
00454     /*
00455     perror("unable to get control");
00456     throw std::runtime_error("unable to get control");
00457     */
00458   }
00459   c.value = val;
00460   if (ioctl(fd, VIDIOC_S_CTRL, &c) < 0)
00461   {
00462     perror("unable to set control");
00463     throw std::runtime_error("unable to set control");
00464   }
00465 }
00466 
00467 void Cam::set_motion_thresholds(int lum, int count)
00468 {
00469   motion_threshold_luminance = lum;
00470   motion_threshold_count = count;
00471 }
00472 
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


uvc_camera_yuv
Author(s): Jochen Sprickerhof/jochen@sprickerhof.de
autogenerated on Thu Apr 25 2013 16:19:21