forked from anqixu/ueye_cam
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathueye_cam_driver.cpp
1638 lines (1412 loc) · 57.9 KB
/
ueye_cam_driver.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/*******************************************************************************
* DO NOT MODIFY - AUTO-GENERATED
*
*
* DISCLAMER:
*
* This project was created within an academic research setting, and thus should
* be considered as EXPERIMENTAL code. There may be bugs and deficiencies in the
* code, so please adjust expectations accordingly. With that said, we are
* intrinsically motivated to ensure its correctness (and often its performance).
* Please use the corresponding web repository tool (e.g. github/bitbucket/etc.)
* to file bugs, suggestions, pull requests; we will do our best to address them
* in a timely manner.
*
*
* SOFTWARE LICENSE AGREEMENT (BSD LICENSE):
*
* Copyright (c) 2013-2016, Anqi Xu and contributors
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the School of Computer Science, McGill University,
* nor the names of its contributors may be used to endorse or promote
* products derived from this software without specific prior written
* permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*******************************************************************************/
#include "ueye_cam/ueye_cam_driver.hpp"
using namespace std;
namespace ueye_cam {
// Note that all of these default settings will be overwritten
// by syncCamConfig() during connectCam()
UEyeCamDriver::UEyeCamDriver(int cam_ID, string cam_name):
cam_handle_(HIDS(0)),
cam_buffer_(nullptr),
cam_buffer_id_(0),
cam_buffer_pitch_(0),
cam_buffer_size_(0),
cam_name_(cam_name),
cam_id_(cam_ID),
cam_subsampling_rate_(1),
cam_binning_rate_(1),
cam_sensor_scaling_rate_(1),
color_mode_(IS_CM_MONO8),
bits_per_pixel_(8) {
cam_aoi_.s32X = 0;
cam_aoi_.s32Y = 0;
cam_aoi_.s32Width = 640;
cam_aoi_.s32Height = 480;
}
UEyeCamDriver::~UEyeCamDriver() {
disconnectCam();
}
INT UEyeCamDriver::connectCam(int new_cam_ID) {
INT is_err = IS_SUCCESS;
int numCameras;
// Terminate any existing opened cameras
setStandbyMode();
// Updates camera ID if specified.
if (new_cam_ID >= 0) {
cam_id_ = new_cam_ID;
}
// Query for number of connected cameras
if ((is_err = is_GetNumberOfCameras(&numCameras)) != IS_SUCCESS) {
ERROR_STREAM("Failed query for number of connected UEye cameras (" <<
err2str(is_err) << ")");
return is_err;
} else if (numCameras < 1) {
ERROR_STREAM("No UEye cameras are connected\n");
ERROR_STREAM("Hint: make sure that the IDS camera daemon (/etc/init.d/ueyeusbdrc) is running\n");
return IS_NO_SUCCESS;
} // NOTE: previously checked if ID < numCameras, but turns out that ID can be arbitrary
// Attempt to open camera handle, and handle case where camera requires a
// mandatory firmware upload
cam_handle_ = static_cast<HIDS>(cam_id_);
if ((is_err = is_InitCamera(&cam_handle_, nullptr)) == IS_STARTER_FW_UPLOAD_NEEDED) {
INT uploadTimeMSEC = 25000;
is_GetDuration (cam_handle_, IS_STARTER_FW_UPLOAD, &uploadTimeMSEC);
INFO_STREAM("Uploading new firmware to [" << cam_name_
<< "]; please wait for about " << uploadTimeMSEC/1000.0 << " seconds");
// Attempt to re-open camera handle while triggering automatic firmware upload
cam_handle_ = static_cast<HIDS>(static_cast<INT>(cam_handle_) | IS_ALLOW_STARTER_FW_UPLOAD);
is_err = is_InitCamera(&cam_handle_, nullptr); // Will block for N seconds
}
if (is_err != IS_SUCCESS) {
ERROR_STREAM("Could not open UEye camera ID " << cam_id_ <<
" (" << err2str(is_err) << ")");
return is_err;
}
// Set display mode to Device Independent Bitmap (DIB)
is_err = is_SetDisplayMode(cam_handle_, IS_SET_DM_DIB);
if (is_err != IS_SUCCESS) {
ERROR_STREAM("UEye camera ID " << cam_id_ <<
" does not support Device Independent Bitmap mode;" <<
" driver wrapper not compatible with OpenGL/DirectX modes (" << err2str(is_err) << ")");
return is_err;
}
// Fetch sensor parameters
is_err = is_GetSensorInfo(cam_handle_, &cam_sensor_info_);
if (is_err != IS_SUCCESS) {
ERROR_STREAM("Could not poll sensor information for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
// Validate camera's configuration to ensure compatibility with driver wrapper
// (note that this function also initializes the internal frame buffer)
if ((is_err = syncCamConfig()) != IS_SUCCESS) return is_err;
DEBUG_STREAM("Connected to [" + cam_name_ + "]");
return is_err;
}
INT UEyeCamDriver::disconnectCam() {
INT is_err = IS_SUCCESS;
if (isConnected()) {
setStandbyMode();
// Release existing camera buffers
if (cam_buffer_ != nullptr) {
is_err = is_FreeImageMem(cam_handle_, cam_buffer_, cam_buffer_id_);
}
cam_buffer_ = nullptr;
// Release camera handle
is_err = is_ExitCamera(cam_handle_);
cam_handle_ = HIDS(0);
DEBUG_STREAM("Disconnected from [" + cam_name_ + "]");
}
return is_err;
}
INT UEyeCamDriver::loadCamConfig(string filename, bool ignore_load_failure) {
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
// Convert filename to unicode, as requested by UEye API
const wstring filenameU(filename.begin(), filename.end());
if ((is_err = is_ParameterSet(cam_handle_, IS_PARAMETERSET_CMD_LOAD_FILE,
(void*) filenameU.c_str(), 0)) != IS_SUCCESS) {
WARN_STREAM("Could not load [" << cam_name_
<< "]'s sensor parameters file " << filename << " (" << err2str(is_err) << ")");
if (ignore_load_failure) is_err = IS_SUCCESS;
return is_err;
} else {
// After loading configuration settings, need to re-ensure that camera's
// current configuration is supported by this driver wrapper
// (note that this function also initializes the internal frame buffer)
if ((is_err = syncCamConfig()) != IS_SUCCESS) return is_err;
DEBUG_STREAM("Successfully loaded sensor parameter file for [" << cam_name_ <<
"]: " << filename);
}
return is_err;
}
INT UEyeCamDriver::setColorMode(string& mode, bool reallocate_buffer) {
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
// Stop capture to prevent access to memory buffer
setStandbyMode();
// Set to specified color mode
color_mode_ = name2colormode(mode);
if (!isSupportedColorMode(color_mode_)) {
WARN_STREAM("Could not set color mode of [" << cam_name_
<< "] to " << mode << " (not supported by this wrapper). "
<< "switching to default mode: mono8");
color_mode_ = IS_CM_MONO8;
mode = "mono8";
}
if ((is_err = is_SetColorMode(cam_handle_, color_mode_)) != IS_SUCCESS) {
ERROR_STREAM("Could not set color mode of [" << cam_name_ <<
"] to " << mode << " (" << err2str(is_err) << ": " << color_mode_ << " / '" << mode << "'). switching to default mode: mono8");
color_mode_ = IS_CM_MONO8;
mode = "mono8";
if ((is_err = is_SetColorMode(cam_handle_, color_mode_)) != IS_SUCCESS) {
ERROR_STREAM("Could not set color mode of [" << cam_name_ <<
"] to " << mode << " (" << err2str(is_err) << ": " << color_mode_ << "/ " << mode << ")");
return is_err;
}
}
bits_per_pixel_ = colormode2bpp(color_mode_);
DEBUG_STREAM("Updated color mode to " << mode << "for [" << cam_name_ << "]");
return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
}
INT UEyeCamDriver::setResolution(INT& image_width, INT& image_height,
INT& image_left, INT& image_top, bool reallocate_buffer) {
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
// Validate arguments
CAP(image_width, 8, static_cast<INT>(cam_sensor_info_.nMaxWidth));
CAP(image_height, 4, static_cast<INT>(cam_sensor_info_.nMaxHeight));
if (image_left >= 0 && static_cast<int>(cam_sensor_info_.nMaxWidth) - image_width - image_left < 0) {
WARN_STREAM("Cannot set AOI left index to " <<
image_left << " with a frame width of " <<
image_width << " and sensor max width of " <<
cam_sensor_info_.nMaxWidth << " for [" << cam_name_ << "]");
image_left = -1;
}
if (image_top >= 0 &&
static_cast<int>(cam_sensor_info_.nMaxHeight) - image_height - image_top < 0) {
WARN_STREAM("Cannot set AOI top index to " <<
image_top << " with a frame height of " <<
image_height << " and sensor max height of " <<
cam_sensor_info_.nMaxHeight << " for [" << cam_name_ << "]");
image_top = -1;
}
cam_aoi_.s32X = (image_left < 0) ?
(cam_sensor_info_.nMaxWidth - static_cast<unsigned int>(image_width)) / 2 : image_left;
cam_aoi_.s32Y = (image_top < 0) ?
(cam_sensor_info_.nMaxHeight - static_cast<unsigned int>(image_height)) / 2 : image_top;
cam_aoi_.s32Width = image_width;
cam_aoi_.s32Height = image_height;
const double s = cam_binning_rate_*cam_subsampling_rate_*cam_sensor_scaling_rate_;
cam_aoi_.s32X /= s;
cam_aoi_.s32Y /= s;
cam_aoi_.s32Width /= s;
cam_aoi_.s32Height /= s;
if ((is_err = is_AOI(cam_handle_, IS_AOI_IMAGE_SET_AOI, &cam_aoi_, sizeof(cam_aoi_))) != IS_SUCCESS) {
ERROR_STREAM("Failed to set Area Of Interest (AOI) to " <<
image_width << " x " << image_height <<
" with top-left corner at (" << cam_aoi_.s32X << ", " << cam_aoi_.s32Y <<
") for [" << cam_name_ << "]" );
return is_err;
}
DEBUG_STREAM("Updated Area Of Interest (AOI) to " <<
image_width << " x " << image_height <<
" with top-left corner at (" << cam_aoi_.s32X << ", " << cam_aoi_.s32Y <<
") for [" << cam_name_ << "]");
return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
}
INT UEyeCamDriver::setSubsampling(int& rate, bool reallocate_buffer) {
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
// Stop capture to prevent access to memory buffer
setStandbyMode();
INT rate_flag;
INT supportedRates;
supportedRates = is_SetSubSampling(cam_handle_, IS_GET_SUPPORTED_SUBSAMPLING);
switch (rate) {
case 1:
rate_flag = IS_SUBSAMPLING_DISABLE;
break;
case 2:
rate_flag = IS_SUBSAMPLING_2X;
break;
case 4:
rate_flag = IS_SUBSAMPLING_4X;
break;
case 8:
rate_flag = IS_SUBSAMPLING_8X;
break;
case 16:
rate_flag = IS_SUBSAMPLING_16X;
break;
default:
WARN_STREAM("[" << cam_name_ << "] currently has unsupported subsampling rate: " <<
rate << ", resetting to 1X");
rate = 1;
rate_flag = IS_SUBSAMPLING_DISABLE;
break;
}
if ((supportedRates & rate_flag) == rate_flag) {
if ((is_err = is_SetSubSampling(cam_handle_, rate_flag)) != IS_SUCCESS) {
ERROR_STREAM("Failed to set subsampling rate to " <<
rate << "X for [" << cam_name_ << "] (" << err2str(is_err) << ")");
return is_err;
}
} else {
WARN_STREAM("[" << cam_name_ << "] does not support requested sampling rate of " << rate);
// Query current rate
INT currRate = is_SetSubSampling(cam_handle_, IS_GET_SUBSAMPLING);
if (currRate == IS_SUBSAMPLING_DISABLE) { rate = 1; }
else if (currRate == IS_SUBSAMPLING_2X) { rate = 2; }
else if (currRate == IS_SUBSAMPLING_4X) { rate = 4; }
else if (currRate == IS_SUBSAMPLING_8X) { rate = 8; }
else if (currRate == IS_SUBSAMPLING_16X) { rate = 16; }
else {
WARN_STREAM("[" << cam_name_ << "] currently has an unsupported sampling rate (" <<
currRate << "), resetting to 1X");
if ((is_err = is_SetSubSampling(cam_handle_, IS_SUBSAMPLING_DISABLE)) != IS_SUCCESS) {
ERROR_STREAM("Failed to set subsampling rate to 1X for [" << cam_name_ << "] (" <<
err2str(is_err) << ")");
return is_err;
}
}
return IS_SUCCESS;
}
DEBUG_STREAM("Updated subsampling rate to " << rate << "X for [" << cam_name_ << "]");
cam_subsampling_rate_ = static_cast<unsigned int>(rate);
return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
}
INT UEyeCamDriver::setBinning(int& rate, bool reallocate_buffer) {
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
// Stop capture to prevent access to memory buffer
setStandbyMode();
INT rate_flag;
INT supportedRates;
supportedRates = is_SetBinning(cam_handle_, IS_GET_SUPPORTED_BINNING);
switch (rate) {
case 1:
rate_flag = IS_BINNING_DISABLE;
break;
case 2:
rate_flag = IS_BINNING_2X;
break;
case 4:
rate_flag = IS_BINNING_4X;
break;
case 8:
rate_flag = IS_BINNING_8X;
break;
case 16:
rate_flag = IS_BINNING_16X;
break;
default:
WARN_STREAM("[" << cam_name_ << "] currently has unsupported binning rate: " <<
rate << ", resetting to 1X");
rate = 1;
rate_flag = IS_BINNING_DISABLE;
break;
}
if ((supportedRates & rate_flag) == rate_flag) {
if ((is_err = is_SetBinning(cam_handle_, rate_flag)) != IS_SUCCESS) {
ERROR_STREAM("Could not set binning rate for [" << cam_name_ << "] to " <<
rate << "X (" << err2str(is_err) << ")");
return is_err;
}
} else {
WARN_STREAM("[" << cam_name_ << "] does not support requested binning rate of " << rate);
// Query current rate
INT currRate = is_SetBinning(cam_handle_, IS_GET_BINNING);
if (currRate == IS_BINNING_DISABLE) { rate = 1; }
else if (currRate == IS_BINNING_2X) { rate = 2; }
else if (currRate == IS_BINNING_4X) { rate = 4; }
else if (currRate == IS_BINNING_8X) { rate = 8; }
else if (currRate == IS_BINNING_16X) { rate = 16; }
else {
WARN_STREAM("[" << cam_name_ << "] currently has an unsupported binning rate (" <<
currRate << "), resetting to 1X");
if ((is_err = is_SetBinning(cam_handle_, IS_BINNING_DISABLE)) != IS_SUCCESS) {
ERROR_STREAM("Failed to set binning rate for [" << cam_name_ << "] to 1X (" <<
err2str(is_err) << ")");
return is_err;
}
}
return IS_SUCCESS;
}
DEBUG_STREAM("Updated binning rate to " << rate << "X for [" << cam_name_ << "]");
cam_binning_rate_ = static_cast<unsigned int>(rate);
return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
}
INT UEyeCamDriver::setSensorScaling(double& rate, bool reallocate_buffer) {
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
// Stop capture to prevent access to memory buffer
setStandbyMode();
SENSORSCALERINFO sensorScalerInfo;
is_err = is_GetSensorScalerInfo(cam_handle_, &sensorScalerInfo, sizeof(sensorScalerInfo));
if (is_err == IS_NOT_SUPPORTED) {
WARN_STREAM("[" << cam_name_ << "] does not support internal image scaling");
rate = 1.0;
cam_sensor_scaling_rate_ = 1.0;
return IS_SUCCESS;
} else if (is_err != IS_SUCCESS) {
ERROR_STREAM("Failed to obtain supported internal image scaling information for [" <<
cam_name_ << "] (" << err2str(is_err) << ")");
rate = 1.0;
cam_sensor_scaling_rate_ = 1.0;
return is_err;
} else {
if (rate < sensorScalerInfo.dblMinFactor || rate > sensorScalerInfo.dblMaxFactor) {
WARN_STREAM("Requested internal image scaling rate of " << rate <<
" is not within supported bounds for [" << cam_name_ << "]: " <<
sensorScalerInfo.dblMinFactor << ", " << sensorScalerInfo.dblMaxFactor <<
"; not updating current rate of " << sensorScalerInfo.dblCurrFactor);
rate = sensorScalerInfo.dblCurrFactor;
return IS_SUCCESS;
}
}
if ((is_err = is_SetSensorScaler(cam_handle_, IS_ENABLE_SENSOR_SCALER, rate)) != IS_SUCCESS) {
WARN_STREAM("Failed to set internal image scaling rate for [" << cam_name_ <<
"] to " << rate << "X (" << err2str(is_err) << "); resetting to 1X");
rate = 1.0;
if ((is_err = is_SetSensorScaler(cam_handle_, IS_ENABLE_SENSOR_SCALER, rate)) != IS_SUCCESS) {
ERROR_STREAM("Failed to set internal image scaling rate for [" << cam_name_ <<
"] to 1X (" << err2str(is_err) << ")");
return is_err;
}
}
DEBUG_STREAM("Updated internal image scaling rate to " << rate << "X for [" << cam_name_ << "]");
cam_sensor_scaling_rate_ = rate;
return (reallocate_buffer ? reallocateCamBuffer() : IS_SUCCESS);
}
INT UEyeCamDriver::setGain(bool& auto_gain, INT& master_gain_prc, INT& red_gain_prc,
INT& green_gain_prc, INT& blue_gain_prc, bool& gain_boost) {
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
// Validate arguments
CAP(master_gain_prc, 0, 100);
CAP(red_gain_prc, 0, 100);
CAP(green_gain_prc, 0, 100);
CAP(blue_gain_prc, 0, 100);
double pval1 = 0, pval2 = 0;
if (auto_gain) {
// Set auto gain
pval1 = 1;
if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_GAIN,
&pval1, &pval2)) != IS_SUCCESS) {
if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_GAIN,
&pval1, &pval2)) != IS_SUCCESS) {
WARN_STREAM("[" << cam_name_ << "] does not support auto gain mode (" << err2str(is_err) << ")");
auto_gain = false;
}
}
} else {
// Disable auto gain
if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_GAIN,
&pval1, &pval2)) != IS_SUCCESS) {
if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_GAIN,
&pval1, &pval2)) != IS_SUCCESS) {
DEBUG_STREAM("[" << cam_name_ << "] does not support auto gain mode (" << err2str(is_err) << ")");
}
}
// Set gain boost
if (is_SetGainBoost(cam_handle_, IS_GET_SUPPORTED_GAINBOOST) != IS_SET_GAINBOOST_ON) {
gain_boost = false;
} else {
if ((is_err = is_SetGainBoost(cam_handle_,
(gain_boost) ? IS_SET_GAINBOOST_ON : IS_SET_GAINBOOST_OFF))
!= IS_SUCCESS) {
WARN_STREAM("Failed to " << ((gain_boost) ? "enable" : "disable") <<
" gain boost for [" << cam_name_ << "] (" << err2str(is_err) << ")");
}
}
// Set manual gain parameters
if ((is_err = is_SetHardwareGain(cam_handle_, master_gain_prc,
red_gain_prc, green_gain_prc, blue_gain_prc)) != IS_SUCCESS) {
WARN_STREAM("Failed to set manual gains (master: " << master_gain_prc <<
"; red: " << red_gain_prc << "; green: " << green_gain_prc <<
"; blue: " << blue_gain_prc << ") for [" << cam_name_ << "] (" <<
err2str(is_err) << ")");
}
}
if (auto_gain) {
DEBUG_STREAM("Updated gain for [" << cam_name_ << "]: auto");
} else {
DEBUG_STREAM("Updated gain for [" << cam_name_ << "]: manual" <<
"\n master gain: " << master_gain_prc <<
"\n red gain: " << red_gain_prc <<
"\n green gain: " << green_gain_prc <<
"\n blue gain: " << blue_gain_prc <<
"\n gain boost: " << gain_boost);
}
return is_err;
}
INT UEyeCamDriver::setSoftwareGamma(INT& software_gamma) {
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
// According to ids this is only possible when the color mode is debayered by the ids driver
if ((color_mode_ == IS_CM_SENSOR_RAW8) ||
(color_mode_ == IS_CM_SENSOR_RAW10) ||
(color_mode_ == IS_CM_SENSOR_RAW12) ||
(color_mode_ == IS_CM_SENSOR_RAW16)) {
WARN_STREAM("Software gamma only possible when the color mode is debayered, " <<
"could not set software gamma for [" << cam_name_ << "]");
return IS_NO_SUCCESS;
}
// set software gamma
if ((is_err = is_Gamma(cam_handle_, IS_GAMMA_CMD_SET, (void*) &software_gamma, sizeof(software_gamma))) != IS_SUCCESS) {
WARN_STREAM("Software gamma could not be set for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
}
return is_err;
}
INT UEyeCamDriver::setExposure(bool& auto_exposure, double& auto_exposure_reference, double& exposure_ms) {
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
double minExposure, maxExposure;
// Set auto exposure
double pval1 = auto_exposure, pval2 = 0;
if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_SHUTTER,
&pval1, &pval2)) != IS_SUCCESS) {
if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SHUTTER,
&pval1, &pval2)) != IS_SUCCESS) {
WARN_STREAM("Auto exposure mode is not supported for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
auto_exposure = false;
}
}
// Set exposure reference for auto exposure controller
if ((is_err = is_SetAutoParameter (cam_handle_, IS_SET_AUTO_REFERENCE,
&auto_exposure_reference, 0)) != IS_SUCCESS) {
WARN_STREAM("Auto exposure reference value could not be set for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
}
// Set manual exposure timing
if (!auto_exposure) {
// Make sure that user-requested exposure rate is achievable
if (((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MIN,
(void*) &minExposure, sizeof(minExposure))) != IS_SUCCESS) ||
((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_GET_EXPOSURE_RANGE_MAX,
(void*) &maxExposure, sizeof(maxExposure))) != IS_SUCCESS)) {
ERROR_STREAM("Failed to query valid exposure range from [" << cam_name_ << "]");
return is_err;
}
CAP(exposure_ms, minExposure, maxExposure);
// Update exposure
if ((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_SET_EXPOSURE,
(void*) &(exposure_ms), sizeof(exposure_ms))) != IS_SUCCESS) {
ERROR_STREAM("Failed to set exposure to " << exposure_ms <<
" ms for [" << cam_name_ << "]");
return is_err;
}
}
DEBUG_STREAM("Updated exposure: " << ((auto_exposure) ? "auto" : to_string(exposure_ms)) <<
" ms for [" << cam_name_ << "]");
return is_err;
}
INT UEyeCamDriver::setWhiteBalance(bool& auto_white_balance, INT& red_offset,
INT& blue_offset) {
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
CAP(red_offset, -50, 50);
CAP(blue_offset, -50, 50);
// Set auto white balance mode and parameters
double pval1 = auto_white_balance, pval2 = 0;
// TODO: 9 bug: enabling auto white balance does not seem to have an effect; in ueyedemo it seems to change R/G/B gains automatically
if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_WHITEBALANCE,
&pval1, &pval2)) != IS_SUCCESS) {
if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_AUTO_WB_ONCE,
&pval1, &pval2)) != IS_SUCCESS) {
WARN_STREAM("Auto white balance mode is not supported for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
auto_white_balance = false;
}
}
if (auto_white_balance) {
pval1 = red_offset;
pval2 = blue_offset;
if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_AUTO_WB_OFFSET,
&pval1, &pval2)) != IS_SUCCESS) {
WARN_STREAM("Failed to set white balance red/blue offsets to " <<
red_offset << " / " << blue_offset <<
" for [" << cam_name_ << "] (" << err2str(is_err) << ")");
}
}
DEBUG_STREAM("Updated white balance for [" << cam_name_ << "]: " <<
((auto_white_balance) ? "auto" : "manual") <<
"\n red offset: " << red_offset <<
"\n blue offset: " << blue_offset);
return is_err;
}
INT UEyeCamDriver::setFrameRate(bool& auto_frame_rate, double& frame_rate_hz) {
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
double pval1 = 0, pval2 = 0;
double minFrameTime, maxFrameTime, intervalFrameTime, newFrameRate;
// Make sure that auto shutter is enabled before enabling auto frame rate
bool autoShutterOn = false;
is_SetAutoParameter(cam_handle_, IS_GET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2);
autoShutterOn |= (pval1 != 0);
is_SetAutoParameter(cam_handle_, IS_GET_ENABLE_AUTO_SHUTTER, &pval1, &pval2);
autoShutterOn |= (pval1 != 0);
if (!autoShutterOn) {
auto_frame_rate = false;
}
// Set frame rate / auto
pval1 = auto_frame_rate;
if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_SENSOR_FRAMERATE,
&pval1, &pval2)) != IS_SUCCESS) {
if ((is_err = is_SetAutoParameter(cam_handle_, IS_SET_ENABLE_AUTO_FRAMERATE,
&pval1, &pval2)) != IS_SUCCESS) {
WARN_STREAM("Auto frame rate mode is not supported for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
auto_frame_rate = false;
}
}
if (!auto_frame_rate) {
// Make sure that user-requested frame rate is achievable
if ((is_err = is_GetFrameTimeRange(cam_handle_, &minFrameTime,
&maxFrameTime, &intervalFrameTime)) != IS_SUCCESS) {
ERROR_STREAM("Failed to query valid frame rate range from [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
CAP(frame_rate_hz, 1.0/maxFrameTime, 1.0/minFrameTime);
// Update frame rate
if ((is_err = is_SetFrameRate(cam_handle_, frame_rate_hz, &newFrameRate)) != IS_SUCCESS) {
ERROR_STREAM("Failed to set frame rate to " << frame_rate_hz <<
" MHz for [" << cam_name_ << "] (" << err2str(is_err) << ")");
return is_err;
} else if (frame_rate_hz != newFrameRate) {
frame_rate_hz = newFrameRate;
}
}
DEBUG_STREAM("Updated frame rate for [" << cam_name_ << "]: " <<
((auto_frame_rate) ? "auto" : to_string(frame_rate_hz)) << " Hz");
return is_err;
}
INT UEyeCamDriver::setPixelClockRate(INT& clock_rate_mhz) {
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
UINT pixelClockList[150]; // No camera has more than 150 different pixel clocks (uEye manual)
UINT numberOfSupportedPixelClocks = 0;
if ((is_err = is_PixelClock(cam_handle_, IS_PIXELCLOCK_CMD_GET_NUMBER,
(void*) &numberOfSupportedPixelClocks, sizeof(numberOfSupportedPixelClocks))) != IS_SUCCESS) {
ERROR_STREAM("Failed to query number of supported pixel clocks from [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
if(numberOfSupportedPixelClocks > 0) {
ZeroMemory(pixelClockList, sizeof(pixelClockList));
if((is_err = is_PixelClock(cam_handle_, IS_PIXELCLOCK_CMD_GET_LIST,
(void*) pixelClockList, numberOfSupportedPixelClocks * sizeof(int))) != IS_SUCCESS) {
ERROR_STREAM("Failed to query list of supported pixel clocks from [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
}
int minPixelClock = static_cast<int>(pixelClockList[0]);
int maxPixelClock = static_cast<int>(pixelClockList[numberOfSupportedPixelClocks-1]);
CAP(clock_rate_mhz, minPixelClock, maxPixelClock);
// As list is sorted smallest to largest...
for(UINT i = 0; i < numberOfSupportedPixelClocks; i++) {
if(clock_rate_mhz <= static_cast<int>(pixelClockList[i])) {
clock_rate_mhz = static_cast<INT>(pixelClockList[i]); // ...get the closest-larger-or-equal from the list
break;
}
}
if ((is_err = is_PixelClock(cam_handle_, IS_PIXELCLOCK_CMD_SET,
(void*) &(clock_rate_mhz), sizeof(clock_rate_mhz))) != IS_SUCCESS) {
ERROR_STREAM("Failed to set pixel clock to " << clock_rate_mhz <<
"MHz for [" << cam_name_ << "] (" << err2str(is_err) << ")");
return is_err;
}
DEBUG_STREAM("Updated pixel clock for [" << cam_name_ << "]: " << clock_rate_mhz << " MHz");
return IS_SUCCESS;
}
INT UEyeCamDriver::setFlashParams(INT& delay_us, UINT& duration_us) {
INT is_err = IS_SUCCESS;
// Make sure parameters are within range supported by camera
IO_FLASH_PARAMS minFlashParams, maxFlashParams, newFlashParams;
if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_GET_PARAMS_MIN,
(void*) &minFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
ERROR_STREAM("Failed to retrieve flash parameter info (min) for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_GET_PARAMS_MAX,
(void*) &maxFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
ERROR_STREAM("Failed to retrieve flash parameter info (max) for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
delay_us = (delay_us < minFlashParams.s32Delay) ? minFlashParams.s32Delay :
((delay_us > maxFlashParams.s32Delay) ? maxFlashParams.s32Delay : delay_us);
duration_us = (duration_us < minFlashParams.u32Duration && duration_us != 0) ? minFlashParams.u32Duration :
((duration_us > maxFlashParams.u32Duration) ? maxFlashParams.u32Duration : duration_us);
newFlashParams.s32Delay = delay_us;
newFlashParams.u32Duration = duration_us;
// WARNING: Setting s32Duration to 0, according to documentation, means
// setting duration to total exposure time. If non-ext-triggered
// camera is operating at fastest grab rate, then the resulting
// flash signal will APPEAR as active LO when set to active HIGH,
// and vice versa. This is why the duration is set manually.
if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_SET_PARAMS,
(void*) &newFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
WARN_STREAM("Failed to set flash parameter info for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
return is_err;
}
INT UEyeCamDriver::setGpioMode(const int& gpio, int& mode, double& pwm_freq, double& pwm_duty_cycle) {
/* Set GPIO to a specific mode. */
INT is_err = IS_SUCCESS;
IO_GPIO_CONFIGURATION gpioConfiguration;
gpioConfiguration.u32State = 0;
IO_PWM_PARAMS m_pwmParams;
if (gpio == 1)
gpioConfiguration.u32Gpio = IO_GPIO_1; // GPIO1 (pin 5).
else if (gpio == 2)
gpioConfiguration.u32Gpio = IO_GPIO_2; // GPIO2 (pin 6).
switch (mode) {
case 0: gpioConfiguration.u32Configuration = IS_GPIO_INPUT; break;
case 1: gpioConfiguration.u32Configuration = IS_GPIO_OUTPUT; break;
case 2:
gpioConfiguration.u32Configuration = IS_GPIO_OUTPUT;
gpioConfiguration.u32State = 1;
break;
case 3: gpioConfiguration.u32Configuration = IS_GPIO_FLASH; break;
case 4:
gpioConfiguration.u32Configuration = IS_GPIO_PWM;
m_pwmParams.dblFrequency_Hz = pwm_freq;
m_pwmParams.dblDutyCycle = pwm_duty_cycle;
break;
case 5: gpioConfiguration.u32Configuration = IS_GPIO_TRIGGER; break;
}
// set GPIO regarding the selected pind and mode
if ((is_err = is_IO(cam_handle_, IS_IO_CMD_GPIOS_SET_CONFIGURATION, (void*)&gpioConfiguration, sizeof(gpioConfiguration))) != IS_SUCCESS) {
ERROR_STREAM("Tried to set GPIO: " << gpioConfiguration.u32Gpio << " and got error code: " << is_err);
}
// Set PWM details if prior change of GPIO was successfull and mode is PWM
if ((is_err == IS_SUCCESS) && (mode == 4)) {
if ((is_err = is_IO(cam_handle_, IS_IO_CMD_PWM_SET_PARAMS, (void*)&m_pwmParams, sizeof(m_pwmParams))) != IS_SUCCESS) {
ERROR_STREAM("Tried to set PWM to: " << m_pwmParams.dblFrequency_Hz << " hz and " << m_pwmParams.dblDutyCycle <<
" % and got error code: " << is_err);
}
}
return is_err;
}
INT UEyeCamDriver::setFreeRunMode() {
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
if (!freeRunModeActive()) {
setStandbyMode(); // No need to check for success
// Set the flash to a high active pulse for each image in the trigger mode
INT flash_delay = 0;
UINT flash_duration = 1000;
setFlashParams(flash_delay, flash_duration);
UINT nMode = IO_FLASH_MODE_FREERUN_HI_ACTIVE;
if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_SET_MODE,
(void*) &nMode, sizeof(nMode))) != IS_SUCCESS) {
WARN_STREAM("Could not set free-run active-low flash output for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
WARN_STREAM("WARNING: camera hardware does not support ueye_cam's master-slave synchronization method");
}
IS_INIT_EVENT init_events[] = {{IS_SET_EVENT_FRAME, FALSE, FALSE}};
if ((is_err = is_Event(cam_handle_, IS_EVENT_CMD_INIT, init_events, sizeof(init_events))) != IS_SUCCESS) {
ERROR_STREAM("Could not init frame event for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
UINT events[] = {IS_SET_EVENT_FRAME};
if ((is_err = is_Event(cam_handle_,IS_EVENT_CMD_ENABLE, events, sizeof(events))) != IS_SUCCESS) {
ERROR_STREAM("Could not enable frame event for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
if ((is_err = is_CaptureVideo(cam_handle_, IS_WAIT)) != IS_SUCCESS) {
ERROR_STREAM("Could not start free-run live video mode for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
DEBUG_STREAM("Started live video mode for [" << cam_name_ << "]");
}
return is_err;
}
INT UEyeCamDriver::setExtTriggerMode() {
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
if (!extTriggerModeActive()) {
setStandbyMode(); // No need to check for success
IS_INIT_EVENT init_events[] = {{IS_SET_EVENT_FRAME, FALSE, FALSE}};
if ((is_err = is_Event(cam_handle_, IS_EVENT_CMD_INIT, init_events, sizeof(init_events))) != IS_SUCCESS) {
ERROR_STREAM("Could not init frame event for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
UINT events[] = {IS_SET_EVENT_FRAME};
if ((is_err = is_Event(cam_handle_,IS_EVENT_CMD_ENABLE, events, sizeof(events))) != IS_SUCCESS) {
ERROR_STREAM("Could not enable frame event for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
if ((is_err = is_SetExternalTrigger(cam_handle_, IS_SET_TRIGGER_HI_LO)) != IS_SUCCESS) {
ERROR_STREAM("Could not enable falling-edge external trigger mode for [" <<
cam_name_ << "] (" << err2str(is_err) << ")");
return is_err;
}
if ((is_err = is_CaptureVideo(cam_handle_, IS_DONT_WAIT)) != IS_SUCCESS) {
ERROR_STREAM("Could not start external trigger live video mode for [" <<
cam_name_ << "] (" << err2str(is_err) << ")");
return is_err;
}
DEBUG_STREAM("Started falling-edge external trigger live video mode for [" <<
cam_name_ << "]");
}
return is_err;
}
INT UEyeCamDriver::setMirrorUpsideDown(bool flip_horizontal){
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
if(flip_horizontal)
is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_UPDOWN,1,0);
else
is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_UPDOWN,0,0);
return is_err;
}
INT UEyeCamDriver::setMirrorLeftRight(bool flip_vertical){
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
if(flip_vertical)
is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_LEFTRIGHT,1,0);
else
is_err = is_SetRopEffect(cam_handle_,IS_SET_ROP_MIRROR_LEFTRIGHT,0,0);
return is_err;
}
INT UEyeCamDriver::setStandbyMode() {
if (!isConnected()) return IS_INVALID_CAMERA_HANDLE;
INT is_err = IS_SUCCESS;
UINT events[] = {IS_SET_EVENT_FRAME};
if (extTriggerModeActive()) {
if ((is_err = is_Event(cam_handle_,IS_EVENT_CMD_DISABLE, events, sizeof(events))) != IS_SUCCESS) {
ERROR_STREAM("Could not disable frame event for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
if ((is_err = is_Event(cam_handle_,IS_EVENT_CMD_EXIT, events, sizeof(events))) != IS_SUCCESS) {
ERROR_STREAM("Could not exit frame event for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
if ((is_err = is_SetExternalTrigger(cam_handle_, IS_SET_TRIGGER_OFF)) != IS_SUCCESS) {
ERROR_STREAM("Could not disable external trigger mode for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
is_SetExternalTrigger(cam_handle_, IS_GET_TRIGGER_STATUS); // documentation seems to suggest that this is needed to disable external trigger mode (to go into free-run mode)