Visual Servoing Platform  version 3.6.1 under development (2024-07-27)
vp1394CMUGrabber.cpp
1 /****************************************************************************
2  *
3  * ViSP, open source Visual Servoing Platform software.
4  * Copyright (C) 2005 - 2023 by Inria. All rights reserved.
5  *
6  * This software is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2 of the License, or
9  * (at your option) any later version.
10  * See the file LICENSE.txt at the root directory of this source
11  * distribution for additional information about the GNU GPL.
12  *
13  * For using ViSP with software that can not be combined with the GNU
14  * GPL, please contact Inria about acquiring a ViSP Professional
15  * Edition License.
16  *
17  * See https://visp.inria.fr for more information.
18  *
19  * This software was developed at:
20  * Inria Rennes - Bretagne Atlantique
21  * Campus Universitaire de Beaulieu
22  * 35042 Rennes Cedex
23  * France
24  *
25  * If you have questions regarding the use of this file, please contact
26  * Inria at visp@inria.fr
27  *
28  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
29  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
30  *
31  * Description:
32  * Firewire cameras video capture based on CMU 1394 Digital Camera SDK.
33  *
34 *****************************************************************************/
35 
36 #include <visp3/core/vpConfig.h>
37 
38 #ifdef VISP_HAVE_CMU1394
39 
40 #include <iostream>
41 
42 #include <visp3/core/vpDebug.h>
43 #include <visp3/core/vpImageConvert.h>
44 #include <visp3/sensor/vp1394CMUGrabber.h>
45 
51  : index(0), // If a camera was not selected the first one (index = 0) will
52  // be used
53  _format(-1), _mode(-1), _fps(-1), _modeauto(true), _gain(0), _shutter(0), _color(vp1394CMUGrabber::UNKNOWN)
54 {
55  // public members
56  init = false;
57 
58  // protected members
59  width = height = -1;
60 
61  // private members
62  camera = new C1394Camera;
63 }
64 
69 {
70  close();
71  // delete camera instance
72  if (camera) {
73  delete camera;
74  camera = nullptr;
75  }
76 }
77 
83 {
84  int camerror;
85 
86  index = cam_id;
87 
88  camerror = camera->SelectCamera(index);
89  if (camerror != CAM_SUCCESS) {
90  switch (camerror) {
91  case CAM_ERROR_PARAM_OUT_OF_RANGE:
92  vpERROR_TRACE("vp1394CMUGrabber error: Found no camera number %i", index);
93  throw(
94  vpFrameGrabberException(vpFrameGrabberException::initializationError, "The required camera is not present"));
95  break;
96  case CAM_ERROR_BUSY:
97  vpERROR_TRACE("vp1394CMUGrabber error: The camera %i is busy", index);
99  "The required camera is in use by other application"));
100  break;
101  case CAM_ERROR:
102  vpERROR_TRACE("vp1394CMUGrabber error: General I/O error when "
103  "selecting camera number %i",
104  index);
105  throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "Resolve camera can not be used"));
106  break;
107  }
108  close();
109  }
110 } // end camera select
111 
115 void vp1394CMUGrabber::initCamera()
116 {
117  if (init == false) {
118  int camerror;
119 
120  if (camera->CheckLink() != CAM_SUCCESS) {
121  vpERROR_TRACE("C1394Camera error: Found no cameras on the 1394 bus");
122  throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "The is no detected camera"));
123  }
124 
125  camerror = camera->InitCamera();
126  if (camerror != CAM_SUCCESS) {
127  switch (camerror) {
128  case CAM_ERROR_NOT_INITIALIZED:
129  vpERROR_TRACE("vp1394CMUGrabber error: No camera selected", index);
130  throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "The is no selected camera"));
131  break;
132  case CAM_ERROR_BUSY:
133  vpERROR_TRACE("vp1394CMUGrabber error: The camera %i is busy", index);
135  "The required camera is in use by other application"));
136  break;
137  case CAM_ERROR:
138  vpERROR_TRACE("vp1394CMUGrabber error: General I/O error when "
139  "selecting camera number %i",
140  index);
141  throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "Resolve camera can not be used"));
142  break;
143  }
144  close();
145  }
146 
147  if (camera->Has1394b())
148  camera->Set1394b(TRUE);
149 
150  // Get the current settings
151  _format = camera->GetVideoFormat();
152  _mode = camera->GetVideoMode();
153  _color = getVideoColorCoding();
154  // std::cout << "format: " << _format << std::endl;
155  // std::cout << "mode: " << _mode << std::endl;
156  // std::cout << "color coding: " << _color << std::endl;
157 
158  // Set trigger off
159  camera->GetCameraControlTrigger()->SetOnOff(false);
160 
161  unsigned long w, h;
162  camera->GetVideoFrameDimensions(&w, &h);
163  this->width = w;
164  this->height = h;
165 
166  // start acquisition
167  if (camera->StartImageAcquisition() != CAM_SUCCESS) {
168  close();
169  vpERROR_TRACE("vp1394CMUGrabber error: Can't start image acquisition "
170  "from IEEE 1394 camera number %i",
171  index);
172  throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Error while starting image acquisition"));
173  }
174 
175  init = true;
176  }
177 
178 } // end camera init
179 
185 {
186  initCamera();
187  I.resize(this->height, this->width);
188 }
189 
195 {
196  initCamera();
197  I.resize(this->height, this->width);
198 }
199 
208 {
209  // get image data
210  unsigned long length;
211  unsigned char *rawdata = nullptr;
212  int dropped;
213  unsigned int size;
214 
215  open(I);
216 
217  camera->AcquireImageEx(TRUE, &dropped);
218  rawdata = camera->GetRawData(&length);
219 
220  size = I.getSize();
221  switch (_color) {
223  memcpy(I.bitmap, (unsigned char *)rawdata, size);
224  break;
226  vpImageConvert::MONO16ToGrey(rawdata, I.bitmap, size);
227  break;
228 
230  vpImageConvert::YUV411ToGrey(rawdata, I.bitmap, size);
231  break;
232 
234  vpImageConvert::YUV422ToGrey(rawdata, I.bitmap, size);
235  break;
236 
238  vpImageConvert::YUV444ToGrey(rawdata, I.bitmap, size);
239  break;
240 
242  vpImageConvert::RGBToGrey(rawdata, I.bitmap, size);
243  break;
244 
245  default:
246  close();
247  vpERROR_TRACE("Format conversion not implemented. Acquisition failed.");
248  throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Format conversion not implemented. "
249  "Acquisition failed."));
250  break;
251  };
252 
253  // unsigned short depth = 0;
254  // camera->GetVideoDataDepth(&depth);
255  // std::cout << "depth: " << depth << " computed: " <<
256  // (float)(length/(I.getHeight() * I.getWidth())) << std::endl;
257 
258  // memcpy(I.bitmap,rawdata,length);
259 }
260 
270 {
271  // get image data
272  unsigned long length;
273  unsigned char *rawdata = nullptr;
274  int dropped;
275  unsigned int size;
276 
277  open(I);
278 
279  camera->AcquireImageEx(TRUE, &dropped);
280  rawdata = camera->GetRawData(&length);
281  size = I.getWidth() * I.getHeight();
282 
283  switch (_color) {
285  vpImageConvert::GreyToRGBa(rawdata, (unsigned char *)I.bitmap, size);
286  break;
287 
289  vpImageConvert::MONO16ToRGBa(rawdata, (unsigned char *)I.bitmap, size);
290  break;
291 
293  vpImageConvert::YUV411ToRGBa(rawdata, (unsigned char *)I.bitmap, size);
294  break;
295 
297  vpImageConvert::YUV422ToRGBa(rawdata, (unsigned char *)I.bitmap, size);
298  break;
299 
301  vpImageConvert::YUV444ToRGBa(rawdata, (unsigned char *)I.bitmap, size);
302  break;
303 
305  size = length / 3;
306  vpImageConvert::RGBToRGBa(rawdata, (unsigned char *)I.bitmap, size);
307  break;
308 
309  default:
310  close();
311  vpERROR_TRACE("Format conversion not implemented. Acquisition failed.");
312  throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Format conversion not implemented. "
313  "Acquisition failed."));
314  break;
315  };
316 }
317 
322 {
323  // stop acquisition
324  if (camera->IsAcquiring()) {
325  // stop acquisition
326  if (camera->StopImageAcquisition() != CAM_SUCCESS) {
327  close();
328  vpERROR_TRACE("vp1394CMUGrabber error: Can't stop image acquisition "
329  "from IEEE 1394 camera number %i",
330  index);
331  throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Error while stopping image acquisition"));
332  }
333  }
334 
335  init = false;
336 }
337 
342 void vp1394CMUGrabber::setControl(unsigned short gain, unsigned short shutter)
343 {
344  setShutter(shutter);
345  setGain(gain);
346 }
347 
352 {
353  int n_cam = camera->RefreshCameraList();
354 
355  return n_cam;
356 }
357 
363 void vp1394CMUGrabber::getGainMinMax(unsigned short &min, unsigned short &max)
364 {
365  initCamera();
366 
367  C1394CameraControl *Control;
368  Control = camera->GetCameraControl(FEATURE_GAIN);
369  Control->Inquire();
370  Control->GetRange(&min, &max);
371 }
378 {
379  initCamera();
380  camera->GetCameraControl(FEATURE_GAIN)->SetAutoMode(true);
381 }
387 void vp1394CMUGrabber::setGain(unsigned short gain)
388 {
389  initCamera();
390  _gain = gain;
391 
392  unsigned short min, max;
393  C1394CameraControl *Control;
394 
395  Control = camera->GetCameraControl(FEATURE_GAIN);
396  Control->Inquire();
397  Control->GetRange(&min, &max);
398 
399  if (_gain < min) {
400  _gain = min;
401  std::cout << "vp1394CMUGrabber warning: Desired gain register value of "
402  "IEEE 1394 camera number "
403  << index << " can't be less than " << _gain << std::endl;
404  }
405  else if (_gain > max) {
406  _gain = max;
407  std::cout << "vp1394CMUGrabber warning: Desired gain register value of "
408  "IEEE 1394 camera number "
409  << index << " can't be greater than " << _gain << std::endl;
410  }
411 
412  Control->SetAutoMode(false);
413  if (Control->SetValue(_gain) != CAM_SUCCESS) {
414  std::cout << "vp1394CMUGrabber warning: Can't set gain register value of "
415  "IEEE 1394 camera number "
416  << index << std::endl;
417  }
418 }
419 
425 void vp1394CMUGrabber::getShutterMinMax(unsigned short &min, unsigned short &max)
426 {
427  initCamera();
428 
429  C1394CameraControl *Control;
430  Control = camera->GetCameraControl(FEATURE_SHUTTER);
431  Control->Inquire();
432  Control->GetRange(&min, &max);
433 }
434 
441 {
442  initCamera();
443  camera->GetCameraControl(FEATURE_SHUTTER)->SetAutoMode(true);
444 }
450 void vp1394CMUGrabber::setShutter(unsigned short shutter)
451 {
452  initCamera();
453 
454  _shutter = shutter;
455 
456  unsigned short min, max;
457  C1394CameraControl *Control;
458 
459  Control = camera->GetCameraControl(FEATURE_SHUTTER);
460  Control->Inquire();
461  Control->GetRange(&min, &max);
462 
463  if (_shutter < min) {
464  _shutter = min;
465  std::cout << "vp1394CMUGrabber warning: Desired exposure time register "
466  "value of IEEE 1394 camera number "
467  << index << " can't be less than " << _shutter << std::endl;
468  }
469  else if (_shutter > max) {
470  _shutter = max;
471  std::cout << "vp1394CMUGrabber warning: Desired exposure time register "
472  "value of IEEE 1394 camera number "
473  << index << " can't be greater than " << _shutter << std::endl;
474  }
475  Control->SetAutoMode(false);
476  if (Control->SetValue(_shutter) != CAM_SUCCESS) {
477  std::cout << "vp1394CMUGrabber warning: Can't set exposure time register "
478  "value of IEEE 1394 camera number "
479  << index << std::endl;
480  }
481 }
482 
487 {
488  if (camera->GetNumberCameras() > cam_id) {
489  char buf[512];
490  camera->GetNodeDescription(cam_id, buf, 512);
491  std::cout << "Camera " << cam_id << ": " << buf << std::endl;
492 
493  }
494  else {
495  std::cout << "Camera " << cam_id << ": camera not found" << std::endl;
496  }
497 }
498 
503 {
504  char vendor[256], model[256], buf[256];
505  LARGE_INTEGER ID;
506 
507  camera->GetCameraName(model, sizeof(model));
508  camera->GetCameraVendor(vendor, sizeof(vendor));
509  camera->GetCameraUniqueID(&ID);
510 
511  std::cout << "Vendor: " << vendor << std::endl;
512  std::cout << "Model: " << model << std::endl;
513 
514  snprintf(buf, 256, "%08X%08X", ID.HighPart, ID.LowPart);
515  std::cout << "UniqueID: " << buf << std::endl;
516 }
517 
557 void vp1394CMUGrabber::setVideoMode(unsigned long format, unsigned long mode)
558 {
559  initCamera();
560 
561  _format = format;
562  _mode = mode;
563 
564  // Set format and mode
565  if ((_format != -1) && (_mode != -1)) {
566  if (!camera->HasVideoMode(_format, _mode)) {
567  close();
568  vpERROR_TRACE("vp1394CMUGrabber error: The image format is not "
569  "supported by the IEEE 1394 camera number %i",
570  index);
571  throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "Video mode not supported"));
572  }
573 
574  if (camera->IsAcquiring()) {
575  // stop acquisition
576  if (camera->StopImageAcquisition() != CAM_SUCCESS) {
577  close();
578  vpERROR_TRACE("vp1394CMUGrabber error: Can't stop image acquisition "
579  "from IEEE 1394 camera number %i",
580  index);
581  throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Error while stopping image acquisition"));
582  }
583  }
584 
585  if (camera->SetVideoFormat(_format) != CAM_SUCCESS) {
586  close();
587  vpERROR_TRACE("vp1394CMUGrabber error: Can't set video format of IEEE "
588  "1394 camera number %i",
589  index);
590  throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "Can't set video format"));
591  }
592 
593  if (camera->SetVideoMode(_mode) != CAM_SUCCESS) {
594  close();
595  vpERROR_TRACE("vp1394CMUGrabber error: Can't set video mode of IEEE "
596  "1394 camera number %i",
597  index);
598  throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "Can't set video mode"));
599  }
600 
601  // start acquisition
602  if (camera->StartImageAcquisition() != CAM_SUCCESS) {
603  close();
604  vpERROR_TRACE("vp1394CMUGrabber error: Can't start image acquisition "
605  "from IEEE 1394 camera number %i",
606  index);
607  throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Error while starting image acquisition"));
608  }
609 
610  // Update Image dimension
611  unsigned long w, h;
612  camera->GetVideoFrameDimensions(&w, &h);
613  this->width = w;
614  this->height = h;
615 
616  // Update the color coding
617  _color = getVideoColorCoding();
618  }
619 }
620 
642 void vp1394CMUGrabber::setFramerate(unsigned long fps)
643 {
644  initCamera();
645 
646  _fps = fps;
647 
648  // Set fps
649  if (_fps != -1) {
650  if (!camera->HasVideoFrameRate(_format, _mode, _fps)) {
651  close();
652  vpERROR_TRACE("vp1394CMUGrabber error: The frame rate is not supported "
653  "by the IEEE 1394 camera number %i for the selected "
654  "image format",
655  index);
656  throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "The frame rate is not supported"));
657  }
658 
659  if (camera->IsAcquiring()) {
660  // stop acquisition
661  if (camera->StopImageAcquisition() != CAM_SUCCESS) {
662  close();
663  vpERROR_TRACE("vp1394CMUGrabber error: Can't stop image acquisition "
664  "from IEEE 1394 camera number %i",
665  index);
666  throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Error while stopping image acquisition"));
667  }
668  }
669  if (camera->SetVideoFrameRate(_fps) != CAM_SUCCESS) {
670  close();
671  vpERROR_TRACE("vp1394CMUGrabber error: Can't set video frame rate of "
672  "IEEE 1394 camera number %i",
673  index);
674  throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "Can't set video frame rate"));
675  }
676  // start acquisition
677  if (camera->StartImageAcquisition() != CAM_SUCCESS) {
678  close();
679  vpERROR_TRACE("vp1394CMUGrabber error: Can't start image acquisition "
680  "from IEEE 1394 camera number %i",
681  index);
682  throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Error while starting image acquisition"));
683  }
684  }
685 }
708 {
709  initCamera();
710  int fps = camera->GetVideoFrameRate();
711  return fps;
712 }
713 
735 {
736  this->acquire(I);
737  return *this;
738 }
739 
761 {
762  this->acquire(I);
763  return *this;
764 }
765 END_VISP_NAMESPACE
766 #elif !defined(VISP_BUILD_SHARED_LIBS)
767 // Work around to avoid warning: libvisp_sensor.a(vp1394CMUGrabber.cpp.o) has
768 // no symbols
769 void dummy_vp1394CMUGrabber() { };
770 #endif
Firewire cameras video capture based on CMU 1394 Digital Camera SDK.
void setControl(unsigned short gain, unsigned short shutter)
virtual ~vp1394CMUGrabber()
void displayCameraDescription(int cam_id)
vpColorCodingType getVideoColorCoding() const
Get the video color coding format.
void getGainMinMax(unsigned short &min, unsigned short &max)
void setVideoMode(unsigned long format, unsigned long mode)
vp1394CMUGrabber & operator>>(vpImage< unsigned char > &I)
void acquire(vpImage< unsigned char > &I)
void setFramerate(unsigned long fps)
void getShutterMinMax(unsigned short &min, unsigned short &max)
int getNumberOfConnectedCameras() const
void setGain(unsigned short gain)
void open(vpImage< unsigned char > &I)
void selectCamera(int cam_id)
void setShutter(unsigned short shutter)
Error that can be emitted by the vpFrameGrabber class and its derivates.
@ settingError
Grabber settings error.
@ initializationError
Grabber initialization error.
@ otherError
Grabber returned an other error.
unsigned int height
Number of rows in the image.
bool init
Set to true if the frame grabber has been initialized.
unsigned int width
Number of columns in the image.
static void YUV411ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size)
static void MONO16ToGrey(unsigned char *grey16, unsigned char *grey, unsigned int size)
static void YUV422ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size)
static void YUV411ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int size)
static void GreyToRGBa(unsigned char *grey, unsigned char *rgba, unsigned int width, unsigned int height)
static void MONO16ToRGBa(unsigned char *grey16, unsigned char *rgba, unsigned int size)
static void RGBToGrey(unsigned char *rgb, unsigned char *grey, unsigned int width, unsigned int height, bool flip=false)
static void RGBToRGBa(unsigned char *rgb, unsigned char *rgba, unsigned int size)
static void YUV422ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int size)
static void YUV444ToRGBa(unsigned char *yuv, unsigned char *rgba, unsigned int size)
static void YUV444ToGrey(unsigned char *yuv, unsigned char *grey, unsigned int size)
unsigned int getWidth() const
Definition: vpImage.h:242
void resize(unsigned int h, unsigned int w)
resize the image : Image initialization
Definition: vpImage.h:538
unsigned int getSize() const
Definition: vpImage.h:221
Type * bitmap
points toward the bitmap
Definition: vpImage.h:135
unsigned int getHeight() const
Definition: vpImage.h:181
#define vpERROR_TRACE
Definition: vpDebug.h:409