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