00001
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 <unistd.h>
00014
00015 #ifndef INT64_C
00016 #define INT64_C(c) (c ## LL)
00017 #define UINT64_C(c) (c ## ULL)
00018 #endif
00019
00020 extern "C" {
00021 #include <linux/videodev2.h>
00022 #include <libavcodec/avcodec.h>
00023 #include <libswscale/swscale.h>
00024 }
00025
00026 static AVFrame *avframe_camera = NULL;
00027 static AVFrame *avframe_rgb = NULL;
00028 static AVCodec *avcodec = NULL;
00029 static AVCodecContext *avcodec_context = NULL;
00030 static int avframe_camera_size = 0;
00031 static int avframe_rgb_size = 0;
00032 struct SwsContext *video_sws = NULL;
00033 unsigned char* jpegBuf = NULL;
00034
00035 using std::string;
00036 using namespace uvc_cam;
00037
00038 Cam::Cam(const char *_device, mode_t _mode, int _width, int _height, int _fps)
00039 : mode(_mode), device(_device),
00040 motion_threshold_luminance(100), motion_threshold_count(-1),
00041 width(_width), height(_height), fps(_fps), rgb_frame(NULL)
00042 {
00043 printf("opening %s\n", _device);
00044 if ((fd = open(_device, O_RDWR)) == -1)
00045 throw std::runtime_error("couldn't open " + device);
00046 memset(&fmt, 0, sizeof(v4l2_format));
00047 memset(&cap, 0, sizeof(v4l2_capability));
00048 if (ioctl(fd, VIDIOC_QUERYCAP, &cap) < 0)
00049 throw std::runtime_error("couldn't query " + device);
00050 if (!(cap.capabilities & V4L2_CAP_VIDEO_CAPTURE))
00051 throw std::runtime_error(device + " does not support capture");
00052 if (!(cap.capabilities & V4L2_CAP_STREAMING))
00053 throw std::runtime_error(device + " does not support streaming");
00054
00055 v4l2_fmtdesc f;
00056 memset(&f, 0, sizeof(f));
00057 f.index = 0;
00058 f.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00059 int ret;
00060 while ((ret = ioctl(fd, VIDIOC_ENUM_FMT, &f)) == 0)
00061 {
00062 printf("pixfmt %d = '%4s' desc = '%s'\n",
00063 f.index++, (char *)&f.pixelformat, f.description);
00064
00065 v4l2_frmsizeenum fsize;
00066 fsize.index = 0;
00067 fsize.pixel_format = f.pixelformat;
00068 while ((ret = ioctl(fd, VIDIOC_ENUM_FRAMESIZES, &fsize)) == 0)
00069 {
00070 fsize.index++;
00071 if (fsize.type == V4L2_FRMSIZE_TYPE_DISCRETE)
00072 {
00073 printf(" discrete: %ux%u: ",
00074 fsize.discrete.width, fsize.discrete.height);
00075
00076 v4l2_frmivalenum fival;
00077 fival.index = 0;
00078 fival.pixel_format = f.pixelformat;
00079 fival.width = fsize.discrete.width;
00080 fival.height = fsize.discrete.height;
00081 while ((ret = ioctl(fd, VIDIOC_ENUM_FRAMEINTERVALS, &fival)) == 0)
00082 {
00083 fival.index++;
00084 if (fival.type == V4L2_FRMIVAL_TYPE_DISCRETE)
00085 {
00086 printf("%u/%u ",
00087 fival.discrete.numerator, fival.discrete.denominator);
00088 }
00089 else
00090 printf("I only handle discrete frame intervals...\n");
00091 }
00092 printf("\n");
00093 }
00094 else if (fsize.type == V4L2_FRMSIZE_TYPE_CONTINUOUS)
00095 {
00096 printf(" continuous: %ux%u to %ux%u\n",
00097 fsize.stepwise.min_width, fsize.stepwise.min_height,
00098 fsize.stepwise.max_width, fsize.stepwise.max_height);
00099 }
00100 else if (fsize.type == V4L2_FRMSIZE_TYPE_STEPWISE)
00101 {
00102 printf(" stepwise: %ux%u to %ux%u step %ux%u\n",
00103 fsize.stepwise.min_width, fsize.stepwise.min_height,
00104 fsize.stepwise.max_width, fsize.stepwise.max_height,
00105 fsize.stepwise.step_width, fsize.stepwise.step_height);
00106 }
00107 else
00108 {
00109 printf(" fsize.type not supported: %d\n", fsize.type);
00110 }
00111 }
00112 }
00113 if (errno != EINVAL)
00114 throw std::runtime_error("error enumerating frame formats");
00115 fmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00116 fmt.fmt.pix.width = width;
00117 fmt.fmt.pix.height = height;
00118 if (mode == MODE_RGB || mode == MODE_YUYV)
00119 fmt.fmt.pix.pixelformat = 'Y' | ('U' << 8) | ('Y' << 16) | ('V' << 24);
00120 else
00121 fmt.fmt.pix.pixelformat = V4L2_PIX_FMT_MJPEG;
00122 fmt.fmt.pix.field = V4L2_FIELD_ANY;
00123 if ((ret = ioctl(fd, VIDIOC_S_FMT, &fmt)) < 0)
00124 throw std::runtime_error("couldn't set format");
00125 if (fmt.fmt.pix.width != width || fmt.fmt.pix.height != height)
00126 throw std::runtime_error("pixel format unavailable");
00127 streamparm.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00128 streamparm.parm.capture.timeperframe.numerator = 1;
00129 streamparm.parm.capture.timeperframe.denominator = fps;
00130 if ((ret = ioctl(fd, VIDIOC_S_PARM, &streamparm)) < 0)
00131 throw std::runtime_error("unable to set framerate");
00132 v4l2_queryctrl queryctrl;
00133 memset(&queryctrl, 0, sizeof(queryctrl));
00134 uint32_t i = V4L2_CID_BASE;
00135 while (i != V4L2_CID_LAST_EXTCTR)
00136 {
00137 queryctrl.id = i;
00138 if ((ret = ioctl(fd, VIDIOC_QUERYCTRL, &queryctrl)) == 0 &&
00139 !(queryctrl.flags & V4L2_CTRL_FLAG_DISABLED))
00140 {
00141 const char *ctrl_type = NULL;
00142 if (queryctrl.type == V4L2_CTRL_TYPE_INTEGER)
00143 ctrl_type = "int";
00144 else if (queryctrl.type == V4L2_CTRL_TYPE_BOOLEAN)
00145 ctrl_type = "bool";
00146 else if (queryctrl.type == V4L2_CTRL_TYPE_BUTTON)
00147 ctrl_type = "button";
00148 else if (queryctrl.type == V4L2_CTRL_TYPE_MENU)
00149 ctrl_type = "menu";
00150 printf(" %s (%s, %d, id = %x): %d to %d (%d)\n",
00151 ctrl_type,
00152 queryctrl.name, queryctrl.flags, queryctrl.id,
00153 queryctrl.minimum, queryctrl.maximum, queryctrl.step);
00154 if (queryctrl.type == V4L2_CTRL_TYPE_MENU)
00155 {
00156 v4l2_querymenu querymenu;
00157 memset(&querymenu, 0, sizeof(querymenu));
00158 querymenu.id = queryctrl.id;
00159 querymenu.index = 0;
00160 while (ioctl(fd, VIDIOC_QUERYMENU, &querymenu) == 0)
00161 {
00162 printf(" %d: %s\n", querymenu.index, querymenu.name);
00163 querymenu.index++;
00164 }
00165 }
00166
00167 }
00168 else if (errno != EINVAL)
00169 throw std::runtime_error("couldn't query control");
00170 i++;
00171 if (i == V4L2_CID_LAST_NEW)
00172 i = V4L2_CID_CAMERA_CLASS_BASE_NEW;
00173 else if (i == V4L2_CID_CAMERA_CLASS_LAST)
00174 i = V4L2_CID_PRIVATE_BASE_OLD;
00175 else if (i == V4L2_CID_PRIVATE_LAST)
00176 i = V4L2_CID_BASE_EXTCTR;
00177 }
00178
00179 try
00180 {
00181
00182
00183 set_control(V4L2_CID_EXPOSURE_AUTO, 3);
00184 set_control(0x009a0903, 1);
00185
00186
00187
00188
00189
00190 set_control(V4L2_CID_BRIGHTNESS, 140);
00191 set_control(V4L2_CID_CONTRAST, 40);
00192 set_control(V4L2_CID_AUTO_WHITE_BALANCE, 1);
00193 set_control(V4L2_CID_GAIN, 120);
00194 set_control(V4L2_CID_SHARPNESS, 140);
00195 set_control(V4L2_CID_SATURATION, 45);
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205
00206
00207
00208
00209 set_control(9963778, 32);
00210 }
00211 catch (std::runtime_error &ex)
00212 {
00213 printf("ERROR: could not set some settings. \n %s \n", ex.what());
00214 }
00215
00216
00217
00218
00219
00220
00221
00222
00223 memset(&rb, 0, sizeof(rb));
00224 rb.count = NUM_BUFFER;
00225 rb.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00226 rb.memory = V4L2_MEMORY_MMAP;
00227 if (ioctl(fd, VIDIOC_REQBUFS, &rb) < 0)
00228 throw std::runtime_error("unable to allocate buffers");
00229 for (unsigned i = 0; i < NUM_BUFFER; i++)
00230 {
00231 memset(&buf, 0, sizeof(buf));
00232 buf.index = i;
00233 buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00234 buf.flags = V4L2_BUF_FLAG_TIMECODE;
00235 buf.timecode = timecode;
00236 buf.timestamp.tv_sec = 0;
00237 buf.timestamp.tv_usec = 0;
00238 buf.memory = V4L2_MEMORY_MMAP;
00239 if (ioctl(fd, VIDIOC_QUERYBUF, &buf) < 0)
00240 throw std::runtime_error("unable to query buffer");
00241 if (buf.length <= 0)
00242 throw std::runtime_error("buffer length is bogus");
00243 mem[i] = mmap(0, buf.length, PROT_READ, MAP_SHARED, fd, buf.m.offset);
00244
00245 if (mem[i] == MAP_FAILED)
00246 throw std::runtime_error("couldn't map buffer");
00247 }
00248 buf_length = buf.length;
00249 for (unsigned i = 0; i < NUM_BUFFER; i++)
00250 {
00251 memset(&buf, 0, sizeof(buf));
00252 buf.index = i;
00253 buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00254 buf.flags = V4L2_BUF_FLAG_TIMECODE;
00255 buf.timecode = timecode;
00256 buf.timestamp.tv_sec = 0;
00257 buf.timestamp.tv_usec = 0;
00258 buf.memory = V4L2_MEMORY_MMAP;
00259 if (ioctl(fd, VIDIOC_QBUF, &buf) < 0)
00260 throw std::runtime_error("unable to queue buffer");
00261 }
00262 int type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00263 if (ioctl(fd, VIDIOC_STREAMON, &type) < 0)
00264 throw std::runtime_error("unable to start capture");
00265 rgb_frame = new unsigned char[width * height * 3];
00266 last_yuv_frame = new unsigned char[width * height * 2];
00267
00268
00269 init_mjpeg_decoder(width, height);
00270 jpegBuf = (unsigned char*) malloc(width*height*3);
00271 }
00272
00273 Cam::~Cam()
00274 {
00275
00276 int type = V4L2_BUF_TYPE_VIDEO_CAPTURE, ret;
00277 if ((ret = ioctl(fd, VIDIOC_STREAMOFF, &type)) < 0)
00278 perror("VIDIOC_STREAMOFF");
00279 for (unsigned i = 0; i < NUM_BUFFER; i++)
00280 if (munmap(mem[i], buf_length) < 0)
00281 perror("failed to unmap buffer");
00282 close(fd);
00283 if (rgb_frame)
00284 {
00285 delete[] rgb_frame;
00286 delete[] last_yuv_frame;
00287 }
00288 last_yuv_frame = rgb_frame = NULL;
00289
00290 if(jpegBuf)
00291 free(jpegBuf);
00292 }
00293
00294 void Cam::enumerate()
00295 {
00296 string v4l_path = "/sys/class/video4linux";
00297 DIR *d = opendir(v4l_path.c_str());
00298 if (!d)
00299 throw std::runtime_error("couldn't open " + v4l_path);
00300 struct dirent *ent, *ent2, *ent3;
00301 int fd, ret;
00302 struct v4l2_capability v4l2_cap;
00303 while ((ent = readdir(d)) != NULL)
00304 {
00305 if (strncmp(ent->d_name, "video", 5))
00306 continue;
00307 string dev_name = string("/dev/") + string(ent->d_name);
00308 printf("enumerating %s ...\n", dev_name.c_str());
00309 if ((fd = open(dev_name.c_str(), O_RDWR)) == -1)
00310 throw std::runtime_error("couldn't open " + dev_name + " perhaps the " +
00311 "permissions are not set correctly?");
00312 if ((ret = ioctl(fd, VIDIOC_QUERYCAP, &v4l2_cap)) < 0)
00313 throw std::runtime_error("couldn't query " + dev_name);
00314 printf("name = [%s]\n", v4l2_cap.card);
00315 printf("driver = [%s]\n", v4l2_cap.driver);
00316 printf("location = [%s]\n", v4l2_cap.bus_info);
00317 close(fd);
00318 string v4l_dev_path = v4l_path + string("/") + string(ent->d_name) +
00319 string("/device");
00320
00321 DIR *d2 = opendir(v4l_dev_path.c_str());
00322 if (!d2)
00323 throw std::runtime_error("couldn't open " + v4l_dev_path);
00324 string input_dir;
00325 while ((ent2 = readdir(d2)) != NULL)
00326 {
00327 if (strncmp(ent2->d_name, "input", 5))
00328 continue;
00329
00330 DIR *input = opendir((v4l_dev_path + string("/") + string(ent2->d_name)).c_str());
00331 bool output_set = false;
00332 while ((ent3 = readdir(input)) != NULL)
00333 {
00334 if (!strncmp(ent3->d_name, "input", 5))
00335 {
00336 input_dir = (string("input/") + string(ent3->d_name )).c_str();
00337 output_set = true;
00338 break;
00339 }
00340 }
00341 if (!output_set)
00342 input_dir = ent2->d_name;
00343 break;
00344 }
00345 closedir(d2);
00346 if (!input_dir.length())
00347 throw std::runtime_error("couldn't find input dir in " + v4l_dev_path);
00348 string vid_fname = v4l_dev_path + string("/") + input_dir +
00349 string("/id/vendor");
00350 string pid_fname = v4l_dev_path + string("/") + input_dir +
00351 string("/id/product");
00352 string ver_fname = v4l_dev_path + string("/") + input_dir +
00353 string("/id/version");
00354 char vid[5], pid[5], ver[5];
00355 FILE *vid_fp = fopen(vid_fname.c_str(), "r");
00356 if (!vid_fp)
00357 throw std::runtime_error("couldn't open " + vid_fname);
00358 if (!fgets(vid, sizeof(vid), vid_fp))
00359 throw std::runtime_error("couldn't read VID from " + vid_fname);
00360 fclose(vid_fp);
00361 vid[4] = 0;
00362 printf("vid = [%s]\n", vid);
00363 FILE *pid_fp = fopen(pid_fname.c_str(), "r");
00364 if (!pid_fp)
00365 throw std::runtime_error("couldn't open " + pid_fname);
00366 if (!fgets(pid, sizeof(pid), pid_fp))
00367 throw std::runtime_error("couldn't read PID from " + pid_fname);
00368 fclose(pid_fp);
00369 printf("pid = [%s]\n", pid);
00370 FILE *ver_fp = fopen(ver_fname.c_str(), "r");
00371 if (!ver_fp)
00372 throw std::runtime_error("couldn't open " + ver_fname);
00373 if (!fgets(ver, sizeof(ver), ver_fp))
00374 throw std::runtime_error("couldn't read version from " + ver_fname);
00375 fclose(ver_fp);
00376 printf("ver = [%s]\n", ver);
00377 }
00378 closedir(d);
00379 }
00380
00381
00382 inline unsigned char sat(float f)
00383 {
00384 return (unsigned char)( f >= 255 ? 255 : (f < 0 ? 0 : f));
00385 }
00386
00387 int Cam::grab(unsigned char **frame, uint32_t &bytes_used)
00388 {
00389 *frame = NULL;
00390 int ret = 0;
00391 fd_set rdset;
00392 timeval timeout;
00393 FD_ZERO(&rdset);
00394 FD_SET(fd, &rdset);
00395 timeout.tv_sec = 1;
00396 timeout.tv_usec = 0;
00397 bytes_used = 0;
00398 ret = select(fd + 1, &rdset, NULL, NULL, &timeout);
00399 if (ret == 0)
00400 {
00401 printf("select timeout in grab\n");
00402 return -1;
00403 }
00404 else if (ret < 0)
00405 {
00406 perror("couldn't grab image");
00407 return -1;
00408 }
00409 if (!FD_ISSET(fd, &rdset))
00410 return -1;
00411 memset(&buf, 0, sizeof(buf));
00412 buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
00413 buf.memory = V4L2_MEMORY_MMAP;
00414 if (ioctl(fd, VIDIOC_DQBUF, &buf) < 0)
00415 throw std::runtime_error("couldn't dequeue buffer");
00416 bytes_used = buf.bytesused;
00417 if (mode == MODE_RGB)
00418 {
00419 int num_pixels_different = 0;
00420 unsigned char *pyuv = (unsigned char *)mem[buf.index];
00421
00422 unsigned char *prgb = rgb_frame;
00423 unsigned char *pyuv_last = last_yuv_frame;
00424 for (unsigned i = 0; i < width * height * 2; i += 4)
00425 {
00426 *prgb++ = sat(pyuv[i]+1.402f *(pyuv[i+3]-128));
00427 *prgb++ = sat(pyuv[i]-0.34414f*(pyuv[i+1]-128)-0.71414f*(pyuv[i+3]-128));
00428 *prgb++ = sat(pyuv[i]+1.772f *(pyuv[i+1]-128));
00429 *prgb++ = sat(pyuv[i+2]+1.402f*(pyuv[i+3]-128));
00430 *prgb++ = sat(pyuv[i+2]-0.34414f*(pyuv[i+1]-128)-0.71414f*(pyuv[i+3]-128));
00431 *prgb++ = sat(pyuv[i+2]+1.772f*(pyuv[i+1]-128));
00432 if ((int)pyuv[i] - (int)pyuv_last[i] > motion_threshold_luminance ||
00433 (int)pyuv_last[i] - (int)pyuv[i] > motion_threshold_luminance)
00434 num_pixels_different++;
00435 if ((int)pyuv[i+2] - (int)pyuv_last[i+2] > motion_threshold_luminance ||
00436 (int)pyuv_last[i+2] - (int)pyuv[i+2] > motion_threshold_luminance)
00437 num_pixels_different++;
00438
00439
00440
00441
00442
00443
00444
00445
00446
00447
00448 }
00449 memcpy(last_yuv_frame, pyuv, width * height * 2);
00450 if (num_pixels_different > motion_threshold_count)
00451 *frame = rgb_frame;
00452 else
00453 {
00454 *frame = NULL;
00455 release(buf.index);
00456 }
00457 }
00458 else if (mode == MODE_YUYV)
00459 {
00460 *frame = (uint8_t *)mem[buf.index];
00461 }
00462 else
00463 {
00464
00465
00466 mjpeg2rgb((char*)mem[buf.index], bytes_used, (char*)jpegBuf, width*height);
00467 *frame = jpegBuf;
00468 }
00469 return buf.index;
00470 }
00471
00472 void Cam::release(unsigned buf_idx)
00473 {
00474 if (buf_idx < NUM_BUFFER)
00475 if (ioctl(fd, VIDIOC_QBUF, &buf) < 0)
00476 throw std::runtime_error("couldn't requeue buffer");
00477 }
00478
00479 void Cam::set_control(uint32_t id, int val)
00480 {
00481 v4l2_control c;
00482 c.id = id;
00483
00484 if (ioctl(fd, VIDIOC_G_CTRL, &c) == 0)
00485 {
00486 printf("current value of %d is %d\n", id, c.value);
00487
00488
00489
00490
00491 }
00492 c.value = val;
00493 if (ioctl(fd, VIDIOC_S_CTRL, &c) < 0)
00494 {
00495 perror("unable to set control");
00496 throw std::runtime_error("unable to set control");
00497 }
00498 }
00499
00500 void Cam::set_motion_thresholds(int lum, int count)
00501 {
00502 motion_threshold_luminance = lum;
00503 motion_threshold_count = count;
00504 }
00505
00506 void Cam::mjpeg2rgb(char *MJPEG, int len, char *RGB, int NumPixels)
00507 {
00508 int got_picture;
00509
00510 memset(RGB, 0, avframe_rgb_size);
00511
00512 #if LIBAVCODEC_VERSION_MAJOR > 52
00513 int decoded_len;
00514 AVPacket avpkt;
00515 av_init_packet(&avpkt);
00516
00517 avpkt.size = len;
00518 avpkt.data = (unsigned char*)MJPEG;
00519 decoded_len = avcodec_decode_video2(avcodec_context, avframe_camera, &got_picture, &avpkt);
00520
00521 if (decoded_len < 0) {
00522 fprintf(stderr, "Error while decoding frame.\n");
00523 return;
00524 }
00525 #else
00526 avcodec_decode_video(avcodec_context, avframe_camera, &got_picture, (uint8_t *) MJPEG, len);
00527 #endif
00528
00529 if (!got_picture) {
00530 fprintf(stderr,"Webcam: expected picture but didn't get it...\n");
00531 return;
00532 }
00533
00534 int xsize = avcodec_context->width;
00535 int ysize = avcodec_context->height;
00536 int pic_size = avpicture_get_size(avcodec_context->pix_fmt, xsize, ysize);
00537 if (pic_size != avframe_camera_size) {
00538 fprintf(stderr,"outbuf size mismatch. pic_size: %d bufsize: %d\n",pic_size,avframe_camera_size);
00539 return;
00540 }
00541
00542 video_sws = sws_getContext( xsize, ysize, avcodec_context->pix_fmt, xsize, ysize, PIX_FMT_RGB24, SWS_BILINEAR, NULL, NULL, NULL);
00543 sws_scale(video_sws, avframe_camera->data, avframe_camera->linesize, 0, ysize, avframe_rgb->data, avframe_rgb->linesize );
00544 sws_freeContext(video_sws);
00545
00546 int size = avpicture_layout((AVPicture *) avframe_rgb, PIX_FMT_RGB24, xsize, ysize, (uint8_t *)RGB, avframe_rgb_size);
00547 if (size != avframe_rgb_size) {
00548 fprintf(stderr,"webcam: avpicture_layout error: %d\n",size);
00549 return;
00550 }
00551 }
00552
00553 int Cam::init_mjpeg_decoder(int image_width, int image_height)
00554 {
00555 avcodec_init();
00556 avcodec_register_all();
00557
00558 avcodec = avcodec_find_decoder(CODEC_ID_MJPEG);
00559 if (!avcodec)
00560 {
00561 fprintf(stderr,"Could not find MJPEG decoder\n");
00562 return 0;
00563 }
00564
00565 avcodec_context = avcodec_alloc_context();
00566 avframe_camera = avcodec_alloc_frame();
00567 avframe_rgb = avcodec_alloc_frame();
00568
00569 avpicture_alloc((AVPicture *)avframe_rgb, PIX_FMT_RGB24, image_width, image_height);
00570
00571 avcodec_context->codec_id = CODEC_ID_MJPEG;
00572 avcodec_context->width = image_width;
00573 avcodec_context->height = image_height;
00574
00575 #if LIBAVCODEC_VERSION_MAJOR > 52
00576 avcodec_context->pix_fmt = PIX_FMT_YUV422P;
00577 avcodec_context->codec_type = AVMEDIA_TYPE_VIDEO;
00578 #endif
00579
00580 avframe_camera_size = avpicture_get_size(PIX_FMT_YUV422P, image_width, image_height);
00581 avframe_rgb_size = avpicture_get_size(PIX_FMT_RGB24, image_width, image_height);
00582
00583
00584 if (avcodec_open(avcodec_context, avcodec) < 0)
00585 {
00586 fprintf(stderr,"Could not open MJPEG Decoder\n");
00587 return 0;
00588 }
00589 return 1;
00590 }