ViSP  2.9.0
vp1394CMUGrabber.cpp
1 /****************************************************************************
2  *
3  * $Id: vp1394CMUGrabber.cpp 4574 2014-01-09 08:48:51Z fspindle $
4  *
5  * This file is part of the ViSP software.
6  * Copyright (C) 2005 - 2014 by INRIA. All rights reserved.
7  *
8  * This software is free software; you can redistribute it and/or
9  * modify it under the terms of the GNU General Public License
10  * ("GPL") version 2 as published by the Free Software Foundation.
11  * See the file LICENSE.txt at the root directory of this source
12  * distribution for additional information about the GNU GPL.
13  *
14  * For using ViSP with software that can not be combined with the GNU
15  * GPL, please contact INRIA about acquiring a ViSP Professional
16  * Edition License.
17  *
18  * See http://www.irisa.fr/lagadic/visp/visp.html for more information.
19  *
20  * This software was developed at:
21  * INRIA Rennes - Bretagne Atlantique
22  * Campus Universitaire de Beaulieu
23  * 35042 Rennes Cedex
24  * France
25  * http://www.irisa.fr/lagadic
26  *
27  * If you have questions regarding the use of this file, please contact
28  * INRIA at visp@inria.fr
29  *
30  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
31  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
32  *
33  *
34  * Description:
35  * Firewire cameras video capture based on CMU 1394 Digital Camera SDK.
36  *
37  * Authors:
38  * Lucas Lopes Lemos FEMTO-ST, AS2M departement, Besancon
39  * Guillaume Laurent FEMTO-ST, AS2M departement, Besancon
40  * Fabien Spindler
41  *
42  *****************************************************************************/
43 
44 #include <visp/vpConfig.h>
45 
46 #ifdef VISP_HAVE_CMU1394
47 
48 #include <iostream>
49 
50 #include <visp/vpImageIo.h>
51 #include <visp/vpImageConvert.h>
52 #include <visp/vp1394CMUGrabber.h>
53 
58 {
59  // public members
60  init = false;
61 
62  // protected members
63  width = height = -1;
64 
65  // private members
66  camera = new C1394Camera;
67  index = 0; // If a camera was not selected the first one (index = 0) will be used
68  _format = _mode = _fps = -1;
69  _modeauto=true;
70 }
71 
76 {
77  close();
78  // delete camera instance
79  if (camera) {
80  delete camera;
81  camera = NULL;
82  }
83 }
84 
89 void
91 {
92  int camerror;
93 
94  index = cam_id ;
95 
96  camerror = camera->SelectCamera(index);
97  if ( camerror!= CAM_SUCCESS)
98  {
99  switch (camerror)
100  {
101  case CAM_ERROR_PARAM_OUT_OF_RANGE:
102  vpERROR_TRACE("vp1394CMUGrabber error: Found no camera number %i",index);
103  throw (vpFrameGrabberException(vpFrameGrabberException::initializationError,"The required camera is not present") );
104  break;
105  case CAM_ERROR_BUSY:
106  vpERROR_TRACE("vp1394CMUGrabber error: The camera %i is busy",index);
107  throw (vpFrameGrabberException(vpFrameGrabberException::initializationError,"The required camera is in use by other application") );
108  break;
109  case CAM_ERROR:
110  vpERROR_TRACE("vp1394CMUGrabber error: General I/O error when selecting camera number %i",index);
111  throw (vpFrameGrabberException(vpFrameGrabberException::initializationError,"Resolve camera can not be used") );
112  break;
113  }
114  close();
115  }
116 } // end camera select
117 
121 void
122 vp1394CMUGrabber::initCamera()
123 {
124  if (init == false)
125  {
126  int camerror;
127 
128  if (camera->CheckLink() != CAM_SUCCESS)
129  {
130  vpERROR_TRACE("C1394Camera error: Found no cameras on the 1394 bus");
131  throw (vpFrameGrabberException(vpFrameGrabberException::initializationError,"The is no detected camera") );
132  }
133 
134  camerror = camera->InitCamera();
135  if ( camerror != CAM_SUCCESS )
136  {
137  switch (camerror)
138  {
139  case CAM_ERROR_NOT_INITIALIZED:
140  vpERROR_TRACE("vp1394CMUGrabber error: No camera selected",index);
141  throw (vpFrameGrabberException(vpFrameGrabberException::initializationError,"The is no selected camera") );
142  break;
143  case CAM_ERROR_BUSY:
144  vpERROR_TRACE("vp1394CMUGrabber error: The camera %i is busy",index);
145  throw (vpFrameGrabberException(vpFrameGrabberException::initializationError,"The required camera is in use by other application") );
146  break;
147  case CAM_ERROR:
148  vpERROR_TRACE("vp1394CMUGrabber error: General I/O error when selecting camera number %i",index);
149  throw (vpFrameGrabberException(vpFrameGrabberException::initializationError,"Resolve camera can not be used") );
150  break;
151  }
152  close();
153  }
154 
155  if (camera->Has1394b())
156  camera->Set1394b(TRUE);
157 
158  // Get the current settings
159  _format = camera->GetVideoFormat();
160  _mode = camera->GetVideoMode();
161  _color = getVideoColorCoding();
162  //std::cout << "format: " << _format << std::endl;
163  //std::cout << "mode: " << _mode << std::endl;
164  //std::cout << "color coding: " << _color << std::endl;
165 
166  // Set trigger off
167  camera->GetCameraControlTrigger()->SetOnOff(false);
168 
169  unsigned long w, h;
170  camera->GetVideoFrameDimensions(&w, &h);
171  this->width = w;
172  this->height = h;
173 
174  // start acquisition
175  if (camera->StartImageAcquisition() != CAM_SUCCESS)
176  {
177  close();
178  vpERROR_TRACE("vp1394CMUGrabber error: Can't start image acquisition from IEEE 1394 camera number %i",index);
180  "Error while starting image acquisition") );
181  }
182 
183  init = true;
184  }
185 
186 } // end camera init
187 
188 
193 void
195 {
196  initCamera();
197  I.resize(this->height, this->width);
198 }
199 
204 void
206 {
207  initCamera();
208  I.resize(this->height, this->width);
209 }
210 
218 void
220 {
221  // get image data
222  unsigned long length;
223  unsigned char *rawdata = NULL ;
224  int dropped;
225  unsigned int size;
226 
227  open(I);
228 
229  camera->AcquireImageEx(TRUE,&dropped);
230  rawdata = camera->GetRawData(&length);
231 
232  size = I.getSize();
233  switch(_color) {
235  memcpy(I.bitmap, (unsigned char *) rawdata, size);
236  break;
238  vpImageConvert::MONO16ToGrey(rawdata, I.bitmap, size);
239  break;
240 
242  vpImageConvert::YUV411ToGrey(rawdata, I.bitmap, size);
243  break;
244 
246  vpImageConvert::YUV422ToGrey(rawdata, I.bitmap, size);
247  break;
248 
250  vpImageConvert::YUV444ToGrey(rawdata, I.bitmap, size);
251  break;
252 
254  vpImageConvert::RGBToGrey(rawdata, I.bitmap, size);
255  break;
256 
257  default:
258  close();
259  vpERROR_TRACE("Format conversion not implemented. Acquisition failed.");
261  "Format conversion not implemented. "
262  "Acquisition failed.") );
263  break;
264  };
265 
266  //unsigned short depth = 0;
267  //camera->GetVideoDataDepth(&depth);
268  //std::cout << "depth: " << depth << " computed: " << (float)(length/(I.getHeight() * I.getWidth())) << std::endl;
269 
270 
271  //memcpy(I.bitmap,rawdata,length);
272 
273 }
274 
283 void
285 {
286  // get image data
287  unsigned long length;
288  unsigned char *rawdata = NULL;
289  int dropped;
290  unsigned int size;
291 
292  open(I);
293 
294  camera->AcquireImageEx(TRUE,&dropped);
295  rawdata = camera->GetRawData(&length);
296  size = I.getWidth() * I.getHeight();
297 
298  switch (_color) {
300  vpImageConvert::GreyToRGBa(rawdata, (unsigned char *)I.bitmap, size);
301  break;
302 
304  vpImageConvert::MONO16ToRGBa(rawdata, (unsigned char *)I.bitmap, size);
305  break;
306 
308  vpImageConvert::YUV411ToRGBa(rawdata, (unsigned char *)I.bitmap, size);
309  break;
310 
312  vpImageConvert::YUV422ToRGBa(rawdata, (unsigned char *)I.bitmap, size);
313  break;
314 
316  vpImageConvert::YUV444ToRGBa(rawdata, (unsigned char *)I.bitmap, size);
317  break;
318 
320  size = length / 3;
321  vpImageConvert::RGBToRGBa(rawdata, (unsigned char *)I.bitmap, size);
322  break;
323 
324  default:
325  close();
326  vpERROR_TRACE("Format conversion not implemented. Acquisition failed.");
328  "Format conversion not implemented. "
329  "Acquisition failed.") );
330  break;
331  };
332 }
333 
337 void
339 {
340  // stop acquisition
341  if (camera->IsAcquiring()) {
342  // stop acquisition
343  if (camera->StopImageAcquisition() != CAM_SUCCESS)
344  {
345  close();
346  vpERROR_TRACE("vp1394CMUGrabber error: Can't stop image acquisition from IEEE 1394 camera number %i",index);
348  "Error while stopping image acquisition") );
349  }
350  }
351 
352  init = false;
353 }
354 
359 void
360 vp1394CMUGrabber::setControl(unsigned short gain, unsigned short shutter)
361 {
362  setShutter(shutter);
363  setGain(gain);
364 }
365 
369 int
371 {
372  int n_cam = camera->RefreshCameraList();
373 
374  return n_cam;
375 }
376 
382 void vp1394CMUGrabber::getGainMinMax(unsigned short &min, unsigned short &max)
383 {
384  initCamera();
385 
386  C1394CameraControl *Control;
387  Control = camera->GetCameraControl(FEATURE_GAIN);
388  Control->Inquire();
389  Control->GetRange(&min, &max);
390 }
397 {
398  initCamera();
399  camera->GetCameraControl(FEATURE_GAIN)->SetAutoMode(true);
400 }
406 void vp1394CMUGrabber::setGain(unsigned short gain)
407 {
408  initCamera();
409  _gain = gain;
410 
411  unsigned short min,max;
412  C1394CameraControl *Control;
413 
414  Control = camera->GetCameraControl(FEATURE_GAIN);
415  Control->Inquire();
416  Control->GetRange(&min,&max);
417 
418  if (_gain < min)
419  {
420  _gain = min;
421  std::cout << "vp1394CMUGrabber warning: Desired gain register value of IEEE 1394 camera number " << index << " can't be less than " << _gain << std::endl;
422  }
423  else if (_gain > max)
424  {
425  _gain = max;
426  std::cout << "vp1394CMUGrabber warning: Desired gain register value of IEEE 1394 camera number " << index << " can't be greater than " << _gain << std::endl;
427  }
428 
429  Control->SetAutoMode(false);
430  if(Control->SetValue(_gain) != CAM_SUCCESS)
431  {
432  std::cout << "vp1394CMUGrabber warning: Can't set gain register value of IEEE 1394 camera number " << index << std::endl;
433  }
434 }
435 
441 void vp1394CMUGrabber::getShutterMinMax(unsigned short &min, unsigned short &max)
442 {
443  initCamera();
444 
445  C1394CameraControl *Control;
446  Control = camera->GetCameraControl(FEATURE_SHUTTER);
447  Control->Inquire();
448  Control->GetRange(&min, &max);
449 }
450 
457 {
458  initCamera();
459  camera->GetCameraControl(FEATURE_SHUTTER)->SetAutoMode(true);
460 }
466 void vp1394CMUGrabber::setShutter(unsigned short shutter)
467 {
468  initCamera();
469 
470  _shutter = shutter;
471 
472  unsigned short min,max;
473  C1394CameraControl *Control;
474 
475  Control = camera->GetCameraControl(FEATURE_SHUTTER);
476  Control->Inquire();
477  Control->GetRange(&min,&max);
478 
479  if (_shutter < min)
480  {
481  _shutter = min;
482  std::cout << "vp1394CMUGrabber warning: Desired exposure time register value of IEEE 1394 camera number " << index << " can't be less than " << _shutter << std::endl;
483  }
484  else if (_shutter > max)
485  {
486  _shutter = max;
487  std::cout << "vp1394CMUGrabber warning: Desired exposure time register value of IEEE 1394 camera number " << index << " can't be greater than " << _shutter << std::endl;
488  }
489  Control->SetAutoMode(false);
490  if(Control->SetValue(_shutter) != CAM_SUCCESS)
491  {
492  std::cout << "vp1394CMUGrabber warning: Can't set exposure time register value of IEEE 1394 camera number " << index << std::endl;
493  }
494 }
495 
499 void
501 {
502  char buf[512];
503 
504  if( camera->GetNumberCameras() > cam_id )
505  {
506  camera->GetNodeDescription(cam_id,buf,512);
507  std::cout << "Camera " << cam_id << ": " << buf << std::endl ;
508 
509  }
510  else {
511  std::cout << "Camera " << cam_id << ": camera not found" << std::endl ;
512  }
513 }
514 
515 
519 void
521 {
522  char vendor[256] , model[256] , buf[256];
523  LARGE_INTEGER ID;
524 
525  camera->GetCameraName(model,sizeof(model));
526  camera->GetCameraVendor(vendor,sizeof(vendor));
527  camera->GetCameraUniqueID(&ID);
528 
529  std::cout << "Vendor: " << vendor << std::endl;
530  std::cout << "Model: " << model << std::endl;
531 
532  sprintf(buf,"%08X%08X",ID.HighPart,ID.LowPart);
533  std::cout << "UniqueID: " << buf << std::endl;
534 
535 }
536 
537 
576 void
577 vp1394CMUGrabber::setVideoMode( unsigned long format, unsigned long mode )
578 {
579  initCamera();
580 
581  _format = format ;
582  _mode = mode ;
583 
584  // Set format and mode
585  if ((_format != -1) && (_mode != -1))
586  {
587  if (!camera->HasVideoMode(_format, _mode))
588  {
589  close();
590  vpERROR_TRACE("vp1394CMUGrabber error: The image format is not supported by the IEEE 1394 camera number %i",index);
591  throw (vpFrameGrabberException(vpFrameGrabberException::settingError,"Video mode not supported") );
592  }
593 
594  if (camera->IsAcquiring()) {
595  // stop acquisition
596  if (camera->StopImageAcquisition() != CAM_SUCCESS)
597  {
598  close();
599  vpERROR_TRACE("vp1394CMUGrabber error: Can't stop image acquisition from IEEE 1394 camera number %i",index);
601  "Error while stopping image acquisition") );
602  }
603  }
604 
605  if (camera->SetVideoFormat(_format) != CAM_SUCCESS)
606  {
607  close();
608  vpERROR_TRACE("vp1394CMUGrabber error: Can't set video format of IEEE 1394 camera number %i",index);
609  throw (vpFrameGrabberException(vpFrameGrabberException::settingError,"Can't set video format") );
610  }
611 
612  if (camera->SetVideoMode(_mode) != CAM_SUCCESS)
613  {
614  close();
615  vpERROR_TRACE("vp1394CMUGrabber error: Can't set video mode of IEEE 1394 camera number %i",index);
616  throw (vpFrameGrabberException(vpFrameGrabberException::settingError,"Can't set video mode") );
617  }
618 
619  // start acquisition
620  if (camera->StartImageAcquisition() != CAM_SUCCESS)
621  {
622  close();
623  vpERROR_TRACE("vp1394CMUGrabber error: Can't start image acquisition from IEEE 1394 camera number %i",index);
625  "Error while starting image acquisition") );
626  }
627 
628  // Update Image dimension
629  unsigned long w, h;
630  camera->GetVideoFrameDimensions(&w, &h);
631  this->width = w;
632  this->height = h;
633 
634  // Update the color coding
635  _color = getVideoColorCoding();
636  }
637 }
638 
660 void
662 {
663  initCamera();
664 
665  _fps = fps;
666 
667  // Set fps
668  if (_fps!=-1)
669  {
670  if (!camera->HasVideoFrameRate(_format,_mode,_fps))
671  {
672  close();
673  vpERROR_TRACE("vp1394CMUGrabber error: The frame rate is not supported by the IEEE 1394 camera number %i for the selected image format",index);
674  throw (vpFrameGrabberException(vpFrameGrabberException::settingError,"The frame rate is not supported") );
675  }
676 
677  if (camera->IsAcquiring()) {
678  // stop acquisition
679  if (camera->StopImageAcquisition() != CAM_SUCCESS)
680  {
681  close();
682  vpERROR_TRACE("vp1394CMUGrabber error: Can't stop image acquisition from IEEE 1394 camera number %i",index);
684  "Error while stopping image acquisition") );
685  }
686  }
687  if (camera->SetVideoFrameRate(_fps) != CAM_SUCCESS)
688  {
689  close();
690  vpERROR_TRACE("vp1394CMUGrabber error: Can't set video frame rate of IEEE 1394 camera number %i",index);
691  throw (vpFrameGrabberException(vpFrameGrabberException::settingError,"Can't set video frame rate") );
692  }
693  // start acquisition
694  if (camera->StartImageAcquisition() != CAM_SUCCESS)
695  {
696  close();
697  vpERROR_TRACE("vp1394CMUGrabber error: Can't start image acquisition from IEEE 1394 camera number %i",index);
699  "Error while starting image acquisition") );
700  }
701 
702  }
703 }
725 int
727 {
728  initCamera();
729  int fps = camera->GetVideoFrameRate();
730  return fps;
731 }
732 
733 #endif
734 
int getNumberOfConnectedCameras() const
void setVideoMode(unsigned long format, unsigned long mode)
static void RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int size)
void setGain(unsigned short gain)
unsigned int getWidth() const
Definition: vpImage.h:159
#define vpERROR_TRACE
Definition: vpDebug.h:395
void open(vpImage< unsigned char > &I)
static void RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int size)
Type * bitmap
points toward the bitmap
Definition: vpImage.h:120
static void MONO16ToGrey(unsigned char *grey16, unsigned char *grey, unsigned int size)
vpColorCodingType getVideoColorCoding() const
Get the video color coding format.
static void GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsigned int size)
static void YUV422ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int size)
Error that can be emited by the vpFrameGrabber class and its derivates.
void setShutter(unsigned short shutter)
void displayCameraDescription(int cam_id)
static void YUV444ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int size)
static void YUV422ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size)
virtual ~vp1394CMUGrabber()
void getGainMinMax(unsigned short &min, unsigned short &max)
void setFramerate(unsigned long fps)
unsigned int getSize() const
Definition: vpImage.h:187
void acquire(vpImage< unsigned char > &I)
unsigned int height
Number of rows in the image.
static void MONO16ToRGBa(unsigned char *grey16, unsigned char *rgba, unsigned int size)
void resize(const unsigned int h, const unsigned int w)
set the size of the image
Definition: vpImage.h:532
bool init
Set to true if the frame grabber has been initialized.
static void YUV444ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size)
void getShutterMinMax(unsigned short &min, unsigned short &max)
static void YUV411ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int size)
unsigned int getHeight() const
Definition: vpImage.h:150
static void YUV411ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size)
unsigned int width
Number of columns in the image.
void setControl(unsigned short gain, unsigned short shutter)
void selectCamera(int cam_id)