Visual Servoing Platform version 3.7.0
Loading...
Searching...
No Matches
vp1394CMUGrabber.cpp
1/*
2 * ViSP, open source Visual Servoing Platform software.
3 * Copyright (C) 2005 - 2025 by Inria. All rights reserved.
4 *
5 * This software is free software; you can redistribute it and/or modify
6 * it under the terms of the GNU General Public License as published by
7 * the Free Software Foundation; either version 2 of the License, or
8 * (at your option) any later version.
9 * See the file LICENSE.txt at the root directory of this source
10 * distribution for additional information about the GNU GPL.
11 *
12 * For using ViSP with software that can not be combined with the GNU
13 * GPL, please contact Inria about acquiring a ViSP Professional
14 * Edition License.
15 *
16 * See https://visp.inria.fr for more information.
17 *
18 * This software was developed at:
19 * Inria Rennes - Bretagne Atlantique
20 * Campus Universitaire de Beaulieu
21 * 35042 Rennes Cedex
22 * France
23 *
24 * If you have questions regarding the use of this file, please contact
25 * Inria at visp@inria.fr
26 *
27 * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28 * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29 *
30 * Description:
31 * Firewire cameras video capture based on CMU 1394 Digital Camera SDK.
32 */
33
34#include <visp3/core/vpConfig.h>
35
36#ifdef VISP_HAVE_CMU1394
37
38#include <iostream>
39
40#include <visp3/core/vpDebug.h>
41#include <visp3/core/vpImageConvert.h>
42#include <visp3/sensor/vp1394CMUGrabber.h>
43
49 : index(0), // If a camera was not selected the first one (index = 0) will
50 // be used
51 _format(-1), _mode(-1), _fps(-1), _modeauto(true), _gain(0), _shutter(0), _color(vp1394CMUGrabber::UNKNOWN)
52{
53 // public members
54 init = false;
55
56 // protected members
57 width = height = -1;
58
59 // private members
60 camera = new C1394Camera;
61}
62
67{
68 close();
69 // delete camera instance
70 if (camera) {
71 delete camera;
72 camera = nullptr;
73 }
74}
75
81{
82 int camerror;
83
84 index = cam_id;
85
86 camerror = camera->SelectCamera(index);
87 if (camerror != CAM_SUCCESS) {
88 switch (camerror) {
89 case CAM_ERROR_PARAM_OUT_OF_RANGE:
90 vpERROR_TRACE("vp1394CMUGrabber error: Found no camera number %i", index);
91 throw(
92 vpFrameGrabberException(vpFrameGrabberException::initializationError, "The required camera is not present"));
93 break;
94 case CAM_ERROR_BUSY:
95 vpERROR_TRACE("vp1394CMUGrabber error: The camera %i is busy", index);
97 "The required camera is in use by other application"));
98 break;
99 case CAM_ERROR:
100 vpERROR_TRACE("vp1394CMUGrabber error: General I/O error when "
101 "selecting camera number %i",
102 index);
103 throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "Resolve camera can not be used"));
104 break;
105 }
106 close();
107 }
108} // end camera select
109
113void vp1394CMUGrabber::initCamera()
114{
115 if (init == false) {
116 int camerror;
117
118 if (camera->CheckLink() != CAM_SUCCESS) {
119 vpERROR_TRACE("C1394Camera error: Found no cameras on the 1394 bus");
121 }
122
123 camerror = camera->InitCamera();
124 if (camerror != CAM_SUCCESS) {
125 switch (camerror) {
126 case CAM_ERROR_NOT_INITIALIZED:
127 vpERROR_TRACE("vp1394CMUGrabber error: No camera selected", index);
128 throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "The is no selected camera"));
129 break;
130 case CAM_ERROR_BUSY:
131 vpERROR_TRACE("vp1394CMUGrabber error: The camera %i is busy", index);
132 throw(vpFrameGrabberException(vpFrameGrabberException::initializationError,
133 "The required camera is in use by other application"));
134 break;
135 case CAM_ERROR:
136 vpERROR_TRACE("vp1394CMUGrabber error: General I/O error when "
137 "selecting camera number %i",
138 index);
139 throw(vpFrameGrabberException(vpFrameGrabberException::initializationError, "Resolve camera can not be used"));
140 break;
141 }
142 close();
143 }
144
145 if (camera->Has1394b())
146 camera->Set1394b(TRUE);
147
148 // Get the current settings
149 _format = camera->GetVideoFormat();
150 _mode = camera->GetVideoMode();
151 _color = getVideoColorCoding();
152 // std::cout << "format: " << _format << std::endl;
153 // std::cout << "mode: " << _mode << std::endl;
154 // std::cout << "color coding: " << _color << std::endl;
155
156 // Set trigger off
157 camera->GetCameraControlTrigger()->SetOnOff(false);
158
159 unsigned long w, h;
160 camera->GetVideoFrameDimensions(&w, &h);
161 this->width = w;
162 this->height = h;
163
164 // start acquisition
165 if (camera->StartImageAcquisition() != CAM_SUCCESS) {
166 close();
167 vpERROR_TRACE("vp1394CMUGrabber error: Can't start image acquisition "
168 "from IEEE 1394 camera number %i",
169 index);
170 throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Error while starting image acquisition"));
171 }
172
173 init = true;
174 }
175
176} // end camera init
177
183{
184 initCamera();
185 I.resize(this->height, this->width);
186}
187
193{
194 initCamera();
195 I.resize(this->height, this->width);
196}
197
206{
207 // get image data
208 unsigned long length;
209 unsigned char *rawdata = nullptr;
210 int dropped;
211 unsigned int size;
212
213 open(I);
214
215 camera->AcquireImageEx(TRUE, &dropped);
216 rawdata = camera->GetRawData(&length);
217
218 size = I.getSize();
219 switch (_color) {
221 memcpy(I.bitmap, (unsigned char *)rawdata, size);
222 break;
224 vpImageConvert::MONO16ToGrey(rawdata, I.bitmap, size);
225 break;
226
228 vpImageConvert::YUV411ToGrey(rawdata, I.bitmap, size);
229 break;
230
232 vpImageConvert::YUV422ToGrey(rawdata, I.bitmap, size);
233 break;
234
236 vpImageConvert::YUV444ToGrey(rawdata, I.bitmap, size);
237 break;
238
240 vpImageConvert::RGBToGrey(rawdata, I.bitmap, size);
241 break;
242
243 default:
244 close();
245 vpERROR_TRACE("Format conversion not implemented. Acquisition failed.");
246 throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Format conversion not implemented. "
247 "Acquisition failed."));
248 break;
249 };
250}
251
261{
262 // get image data
263 unsigned long length;
264 unsigned char *rawdata = nullptr;
265 int dropped;
266 unsigned int size;
267
268 open(I);
269
270 camera->AcquireImageEx(TRUE, &dropped);
271 rawdata = camera->GetRawData(&length);
272 size = I.getWidth() * I.getHeight();
273
274 switch (_color) {
276 vpImageConvert::GreyToRGBa(rawdata, (unsigned char *)I.bitmap, size);
277 break;
278
280 vpImageConvert::MONO16ToRGBa(rawdata, (unsigned char *)I.bitmap, size);
281 break;
282
284 vpImageConvert::YUV411ToRGBa(rawdata, (unsigned char *)I.bitmap, size);
285 break;
286
288 vpImageConvert::YUV422ToRGBa(rawdata, (unsigned char *)I.bitmap, size);
289 break;
290
292 vpImageConvert::YUV444ToRGBa(rawdata, (unsigned char *)I.bitmap, size);
293 break;
294
296 size = length / 3;
297 vpImageConvert::RGBToRGBa(rawdata, (unsigned char *)I.bitmap, size);
298 break;
299
300 default:
301 close();
302 vpERROR_TRACE("Format conversion not implemented. Acquisition failed.");
303 throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Format conversion not implemented. "
304 "Acquisition failed."));
305 break;
306 };
307}
308
313{
314 // stop acquisition
315 if (camera->IsAcquiring()) {
316 // stop acquisition
317 if (camera->StopImageAcquisition() != CAM_SUCCESS) {
318 close();
319 vpERROR_TRACE("vp1394CMUGrabber error: Can't stop image acquisition "
320 "from IEEE 1394 camera number %i",
321 index);
322 throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Error while stopping image acquisition"));
323 }
324 }
325
326 init = false;
327}
328
333void vp1394CMUGrabber::setControl(unsigned short gain, unsigned short shutter)
334{
335 setShutter(shutter);
336 setGain(gain);
337}
338
343{
344 int n_cam = camera->RefreshCameraList();
345
346 return n_cam;
347}
348
354void vp1394CMUGrabber::getGainMinMax(unsigned short &min, unsigned short &max)
355{
356 initCamera();
357
358 C1394CameraControl *Control;
359 Control = camera->GetCameraControl(FEATURE_GAIN);
360 Control->Inquire();
361 Control->GetRange(&min, &max);
362}
363
369{
370 initCamera();
371 camera->GetCameraControl(FEATURE_GAIN)->SetAutoMode(true);
372}
373
378void vp1394CMUGrabber::setGain(unsigned short gain)
379{
380 initCamera();
381 _gain = gain;
382
383 unsigned short min, max;
384 C1394CameraControl *Control;
385
386 Control = camera->GetCameraControl(FEATURE_GAIN);
387 Control->Inquire();
388 Control->GetRange(&min, &max);
389
390 if (_gain < min) {
391 _gain = min;
392 std::cout << "vp1394CMUGrabber warning: Desired gain register value of "
393 "IEEE 1394 camera number "
394 << index << " can't be less than " << _gain << std::endl;
395 }
396 else if (_gain > max) {
397 _gain = max;
398 std::cout << "vp1394CMUGrabber warning: Desired gain register value of "
399 "IEEE 1394 camera number "
400 << index << " can't be greater than " << _gain << std::endl;
401 }
402
403 Control->SetAutoMode(false);
404 if (Control->SetValue(_gain) != CAM_SUCCESS) {
405 std::cout << "vp1394CMUGrabber warning: Can't set gain register value of "
406 "IEEE 1394 camera number "
407 << index << std::endl;
408 }
409}
410
416void vp1394CMUGrabber::getShutterMinMax(unsigned short &min, unsigned short &max)
417{
418 initCamera();
419
420 C1394CameraControl *Control;
421 Control = camera->GetCameraControl(FEATURE_SHUTTER);
422 Control->Inquire();
423 Control->GetRange(&min, &max);
424}
425
432{
433 initCamera();
434 camera->GetCameraControl(FEATURE_SHUTTER)->SetAutoMode(true);
435}
436
441void vp1394CMUGrabber::setShutter(unsigned short shutter)
442{
443 initCamera();
444
445 _shutter = shutter;
446
447 unsigned short min, max;
448 C1394CameraControl *Control;
449
450 Control = camera->GetCameraControl(FEATURE_SHUTTER);
451 Control->Inquire();
452 Control->GetRange(&min, &max);
453
454 if (_shutter < min) {
455 _shutter = min;
456 std::cout << "vp1394CMUGrabber warning: Desired exposure time register "
457 "value of IEEE 1394 camera number "
458 << index << " can't be less than " << _shutter << std::endl;
459 }
460 else if (_shutter > max) {
461 _shutter = max;
462 std::cout << "vp1394CMUGrabber warning: Desired exposure time register "
463 "value of IEEE 1394 camera number "
464 << index << " can't be greater than " << _shutter << std::endl;
465 }
466 Control->SetAutoMode(false);
467 if (Control->SetValue(_shutter) != CAM_SUCCESS) {
468 std::cout << "vp1394CMUGrabber warning: Can't set exposure time register "
469 "value of IEEE 1394 camera number "
470 << index << std::endl;
471 }
472}
473
478{
479 if (camera->GetNumberCameras() > cam_id) {
480 char buf[512];
481 camera->GetNodeDescription(cam_id, buf, 512);
482 std::cout << "Camera " << cam_id << ": " << buf << std::endl;
483
484 }
485 else {
486 std::cout << "Camera " << cam_id << ": camera not found" << std::endl;
487 }
488}
489
494{
495 char vendor[256], model[256], buf[256];
496 LARGE_INTEGER ID;
497
498 camera->GetCameraName(model, sizeof(model));
499 camera->GetCameraVendor(vendor, sizeof(vendor));
500 camera->GetCameraUniqueID(&ID);
501
502 std::cout << "Vendor: " << vendor << std::endl;
503 std::cout << "Model: " << model << std::endl;
504
505 snprintf(buf, 256, "%08X%08X", ID.HighPart, ID.LowPart);
506 std::cout << "UniqueID: " << buf << std::endl;
507}
508
548void vp1394CMUGrabber::setVideoMode(unsigned long format, unsigned long mode)
549{
550 initCamera();
551
552 _format = format;
553 _mode = mode;
554
555 // Set format and mode
556 if ((_format != -1) && (_mode != -1)) {
557 if (!camera->HasVideoMode(_format, _mode)) {
558 close();
559 vpERROR_TRACE("vp1394CMUGrabber error: The image format is not "
560 "supported by the IEEE 1394 camera number %i",
561 index);
562 throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "Video mode not supported"));
563 }
564
565 if (camera->IsAcquiring()) {
566 // stop acquisition
567 if (camera->StopImageAcquisition() != CAM_SUCCESS) {
568 close();
569 vpERROR_TRACE("vp1394CMUGrabber error: Can't stop image acquisition "
570 "from IEEE 1394 camera number %i",
571 index);
572 throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Error while stopping image acquisition"));
573 }
574 }
575
576 if (camera->SetVideoFormat(_format) != CAM_SUCCESS) {
577 close();
578 vpERROR_TRACE("vp1394CMUGrabber error: Can't set video format of IEEE "
579 "1394 camera number %i",
580 index);
581 throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "Can't set video format"));
582 }
583
584 if (camera->SetVideoMode(_mode) != CAM_SUCCESS) {
585 close();
586 vpERROR_TRACE("vp1394CMUGrabber error: Can't set video mode of IEEE "
587 "1394 camera number %i",
588 index);
590 }
591
592 // start acquisition
593 if (camera->StartImageAcquisition() != CAM_SUCCESS) {
594 close();
595 vpERROR_TRACE("vp1394CMUGrabber error: Can't start image acquisition "
596 "from IEEE 1394 camera number %i",
597 index);
598 throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Error while starting image acquisition"));
599 }
600
601 // Update Image dimension
602 unsigned long w, h;
603 camera->GetVideoFrameDimensions(&w, &h);
604 this->width = w;
605 this->height = h;
606
607 // Update the color coding
608 _color = getVideoColorCoding();
609 }
610}
611
633void vp1394CMUGrabber::setFramerate(unsigned long fps)
634{
635 initCamera();
636
637 _fps = fps;
638
639 // Set fps
640 if (_fps != -1) {
641 if (!camera->HasVideoFrameRate(_format, _mode, _fps)) {
642 close();
643 vpERROR_TRACE("vp1394CMUGrabber error: The frame rate is not supported "
644 "by the IEEE 1394 camera number %i for the selected "
645 "image format",
646 index);
647 throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "The frame rate is not supported"));
648 }
649
650 if (camera->IsAcquiring()) {
651 // stop acquisition
652 if (camera->StopImageAcquisition() != CAM_SUCCESS) {
653 close();
654 vpERROR_TRACE("vp1394CMUGrabber error: Can't stop image acquisition "
655 "from IEEE 1394 camera number %i",
656 index);
657 throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Error while stopping image acquisition"));
658 }
659 }
660 if (camera->SetVideoFrameRate(_fps) != CAM_SUCCESS) {
661 close();
662 vpERROR_TRACE("vp1394CMUGrabber error: Can't set video frame rate of "
663 "IEEE 1394 camera number %i",
664 index);
665 throw(vpFrameGrabberException(vpFrameGrabberException::settingError, "Can't set video frame rate"));
666 }
667 // start acquisition
668 if (camera->StartImageAcquisition() != CAM_SUCCESS) {
669 close();
670 vpERROR_TRACE("vp1394CMUGrabber error: Can't start image acquisition "
671 "from IEEE 1394 camera number %i",
672 index);
673 throw(vpFrameGrabberException(vpFrameGrabberException::otherError, "Error while starting image acquisition"));
674 }
675 }
676}
677
699{
700 initCamera();
701 int fps = camera->GetVideoFrameRate();
702 return fps;
703}
704
730
752{
753 this->acquire(I);
754 return *this;
755}
756END_VISP_NAMESPACE
757#elif !defined(VISP_BUILD_SHARED_LIBS)
758// Work around to avoid warning: libvisp_sensor.a(vp1394CMUGrabber.cpp.o) has
759// no symbols
760void dummy_vp1394CMUGrabber() { }
761#endif
void setControl(unsigned short gain, unsigned short shutter)
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)
Definition of the vpImage class member functions.
Definition vpImage.h:131
#define vpERROR_TRACE
Definition vpDebug.h:423