forked from anqixu/ueye_cam
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathueye_cam_nodelet.cpp
1344 lines (1197 loc) · 55.7 KB
/
ueye_cam_nodelet.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_nodelet.hpp"
#include <cstdlib> // needed for getenv()
#include <ros/package.h>
#include <camera_calibration_parsers/parse.h>
#include <std_msgs/UInt64.h>
#include <sensor_msgs/fill_image.h>
#include <sensor_msgs/image_encodings.h>
//#define DEBUG_PRINTOUT_FRAME_GRAB_RATES
using namespace std;
using namespace sensor_msgs::image_encodings;
namespace ueye_cam {
const std::string UEyeCamNodelet::DEFAULT_FRAME_NAME = "camera";
const std::string UEyeCamNodelet::DEFAULT_CAMERA_NAME = "camera";
const std::string UEyeCamNodelet::DEFAULT_CAMERA_TOPIC = "image_raw";
const std::string UEyeCamNodelet::DEFAULT_TIMEOUT_TOPIC = "timeout_count";
const std::string UEyeCamNodelet::DEFAULT_COLOR_MODE = "";
constexpr int UEyeCamDriver::ANY_CAMERA; // Needed since CMakeLists.txt creates 2 separate libraries: one for non-ROS parent class, and one for ROS child class
// Note that these default settings will be overwritten by queryCamParams() during connectCam()
UEyeCamNodelet::UEyeCamNodelet():
nodelet::Nodelet(),
UEyeCamDriver(ANY_CAMERA, DEFAULT_CAMERA_NAME),
frame_grab_alive_(false),
ros_cfg_(nullptr),
cfg_sync_requested_(false),
ros_frame_count_(0),
timeout_count_(0),
cam_topic_(DEFAULT_CAMERA_TOPIC),
timeout_topic_(DEFAULT_TIMEOUT_TOPIC),
cam_intr_filename_(""),
cam_params_filename_(""),
init_clock_tick_(0),
init_publish_time_(0),
prev_output_frame_idx_(0) {
ros_image_.is_bigendian = (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__); // TODO: what about MS Windows?
cam_params_.image_width = DEFAULT_IMAGE_WIDTH;
cam_params_.image_height = DEFAULT_IMAGE_HEIGHT;
cam_params_.image_left = -1;
cam_params_.image_top = -1;
cam_params_.color_mode = DEFAULT_COLOR_MODE;
cam_params_.subsampling = static_cast<int>(cam_subsampling_rate_);
cam_params_.binning = static_cast<int>(cam_binning_rate_);
cam_params_.sensor_scaling = cam_sensor_scaling_rate_;
cam_params_.auto_gain = false;
cam_params_.master_gain = 0;
cam_params_.red_gain = 0;
cam_params_.green_gain = 0;
cam_params_.blue_gain = 0;
cam_params_.gain_boost = 0;
cam_params_.software_gamma=100;
cam_params_.auto_exposure = false;
cam_params_.auto_exposure_reference = 128;
cam_params_.exposure = DEFAULT_EXPOSURE;
cam_params_.auto_white_balance = false;
cam_params_.white_balance_red_offset = 0;
cam_params_.white_balance_blue_offset = 0;
cam_params_.auto_frame_rate = false;
cam_params_.frame_rate = DEFAULT_FRAME_RATE;
cam_params_.output_rate = 0; // disable by default
cam_params_.pixel_clock = DEFAULT_PIXEL_CLOCK;
cam_params_.ext_trigger_mode = false;
cam_params_.flash_delay = 0;
cam_params_.flash_duration = DEFAULT_FLASH_DURATION;
cam_params_.gpio1 = 0;
cam_params_.gpio2 = 0;
cam_params_.pwm_freq = 1;
cam_params_.pwm_duty_cycle=0.5;
cam_params_.flip_upd = false;
cam_params_.flip_lr = false;
}
UEyeCamNodelet::~UEyeCamNodelet() {
disconnectCam();
// NOTE: sometimes deleting dynamic reconfigure object will lock up
// (suspect the scoped lock is not releasing the recursive mutex)
//
//if (ros_cfg_ != NULL) {
// delete ros_cfg_;
// ros_cfg_ = NULL;
//}
}
void UEyeCamNodelet::onInit() {
ros::NodeHandle& nh = getNodeHandle();
ros::NodeHandle& local_nh = getPrivateNodeHandle();
image_transport::ImageTransport it(nh);
// Load camera-agnostic ROS parameters
local_nh.param<string>("camera_name", cam_name_, DEFAULT_CAMERA_NAME);
local_nh.param<string>("frame_name", frame_name_, DEFAULT_FRAME_NAME);
local_nh.param<string>("camera_topic", cam_topic_, DEFAULT_CAMERA_TOPIC);
local_nh.param<string>("timeout_topic", timeout_topic_, DEFAULT_TIMEOUT_TOPIC);
local_nh.param<string>("camera_intrinsics_file", cam_intr_filename_, "");
local_nh.param<int>("camera_id", cam_id_, ANY_CAMERA);
local_nh.param<string>("camera_parameters_file", cam_params_filename_, "");
if (cam_id_ < 0) {
WARN_STREAM("Invalid camera ID specified: " << cam_id_ <<
"; setting to ANY_CAMERA");
cam_id_ = ANY_CAMERA;
}
loadIntrinsicsFile();
// Setup publishers, subscribers, and services
ros_cam_pub_ = it.advertiseCamera(cam_name_ + "/" + cam_topic_, 1);
set_cam_info_srv_ = nh.advertiseService(cam_name_ + "/set_camera_info",
&UEyeCamNodelet::setCamInfo, this);
timeout_pub_ = nh.advertise<std_msgs::UInt64>(cam_name_ + "/" + timeout_topic_, 1, true);
std_msgs::UInt64 timeout_msg; timeout_msg.data = 0; timeout_pub_.publish(timeout_msg);
// Initiate camera and start capture
if (connectCam() != IS_SUCCESS) {
ERROR_STREAM("Failed to initialize [" << cam_name_ << "]");
return;
}
// Setup dynamic reconfigure server
ros_cfg_ = new ReconfigureServer(ros_cfg_mutex_, local_nh);
ReconfigureServer::CallbackType f;
f = bind(&UEyeCamNodelet::configCallback, this, _1, _2);
ros_cfg_->setCallback(f); // this will call configCallback, which will configure the camera's parameters
startFrameGrabber();
INFO_STREAM(
"UEye camera [" << cam_name_ << "] initialized on topic " << ros_cam_pub_.getTopic() << endl <<
"Width:\t\t\t" << cam_params_.image_width << endl <<
"Height:\t\t\t" << cam_params_.image_height << endl <<
"Left Pos.:\t\t" << cam_params_.image_left << endl <<
"Top Pos.:\t\t" << cam_params_.image_top << endl <<
"Color Mode:\t\t" << cam_params_.color_mode << endl <<
"Subsampling:\t\t" << cam_params_.subsampling << endl <<
"Binning:\t\t" << cam_params_.binning << endl <<
"Sensor Scaling:\t\t" << cam_params_.sensor_scaling << endl <<
"Auto Gain:\t\t" << cam_params_.auto_gain << endl <<
"Master Gain:\t\t" << cam_params_.master_gain << endl <<
"Red Gain:\t\t" << cam_params_.red_gain << endl <<
"Green Gain:\t\t" << cam_params_.green_gain << endl <<
"Blue Gain:\t\t" << cam_params_.blue_gain << endl <<
"Gain Boost:\t\t" << cam_params_.gain_boost << endl <<
"Software Gamma:\t\t" << cam_params_.software_gamma << endl <<
"Auto Exposure:\t\t" << cam_params_.auto_exposure << endl <<
"Auto Exposure Reference:\t" << cam_params_.auto_exposure_reference << endl <<
"Exposure (ms):\t\t" << cam_params_.exposure << endl <<
"Auto White Balance:\t" << cam_params_.auto_white_balance << endl <<
"WB Red Offset:\t\t" << cam_params_.white_balance_red_offset << endl <<
"WB Blue Offset:\t\t" << cam_params_.white_balance_blue_offset << endl <<
"Flash Delay (us):\t" << cam_params_.flash_delay << endl <<
"Flash Duration (us):\t" << cam_params_.flash_duration << endl <<
"Ext Trigger Mode:\t" << cam_params_.ext_trigger_mode << endl <<
"Auto Frame Rate:\t" << cam_params_.auto_frame_rate << endl <<
"Frame Rate (Hz):\t" << cam_params_.frame_rate << endl <<
"Output Rate (Hz):\t" << cam_params_.output_rate << endl <<
"Pixel Clock (MHz):\t" << cam_params_.pixel_clock << endl <<
"GPIO1 Mode:\t" << cam_params_.gpio1 << endl <<
"GPIO2 Mode:\t" << cam_params_.gpio2 << endl <<
"Mirror Image Upside Down:\t" << cam_params_.flip_upd << endl <<
"Mirror Image Left Right:\t" << cam_params_.flip_lr << endl
);
}
INT UEyeCamNodelet::parseROSParams(ros::NodeHandle& local_nh) {
bool hasNewParams = false;
ueye_cam::UEyeCamConfig prevCamParams = cam_params_;
INT is_err = IS_SUCCESS;
if (local_nh.hasParam("image_width")) {
local_nh.getParam("image_width", cam_params_.image_width);
if (cam_params_.image_width != prevCamParams.image_width) {
if (cam_params_.image_width <= 0) {
WARN_STREAM("Invalid requested image width for [" << cam_name_ <<
"]: " << cam_params_.image_width <<
"; using current width: " << prevCamParams.image_width);
cam_params_.image_width = prevCamParams.image_width;
} else {
hasNewParams = true;
}
}
} else {
local_nh.setParam("image_width", cam_params_.image_width);
}
if (local_nh.hasParam("image_height")) {
local_nh.getParam("image_height", cam_params_.image_height);
if (cam_params_.image_height != prevCamParams.image_height) {
if (cam_params_.image_height <= 0) {
WARN_STREAM("Invalid requested image height for [" << cam_name_ <<
"]: " << cam_params_.image_height <<
"; using current height: " << prevCamParams.image_height);
cam_params_.image_height = prevCamParams.image_height;
} else {
hasNewParams = true;
}
}
} else {
local_nh.setParam("image_height", cam_params_.image_height);
}
if (local_nh.hasParam("image_top")) {
local_nh.getParam("image_top", cam_params_.image_top);
if (cam_params_.image_top != prevCamParams.image_top) {
hasNewParams = true;
}
} else {
local_nh.setParam("image_top", cam_params_.image_top);
}
if (local_nh.hasParam("image_left")) {
local_nh.getParam("image_left", cam_params_.image_left);
if (cam_params_.image_left != prevCamParams.image_left) {
hasNewParams = true;
}
} else {
local_nh.setParam("image_left", cam_params_.image_left);
}
if (local_nh.hasParam("color_mode")) {
local_nh.getParam("color_mode", cam_params_.color_mode);
if (cam_params_.color_mode != prevCamParams.color_mode) {
if (cam_params_.color_mode.length() > 0) {
transform(cam_params_.color_mode.begin(),
cam_params_.color_mode.end(),
cam_params_.color_mode.begin(),
::tolower);
if (name2colormode(cam_params_.color_mode) != 0) {
hasNewParams = true;
} else {
WARN_STREAM("Invalid requested color mode for [" << cam_name_
<< "]: " << cam_params_.color_mode
<< "; using current mode: " << prevCamParams.color_mode);
cam_params_.color_mode = prevCamParams.color_mode;
}
} else { // Empty requested color mode string
cam_params_.color_mode = prevCamParams.color_mode;
}
}
} else {
local_nh.setParam("color_mode", cam_params_.color_mode);
}
if (local_nh.hasParam("subsampling")) {
local_nh.getParam("subsampling", cam_params_.subsampling);
if (cam_params_.subsampling != prevCamParams.subsampling) {
if (!(cam_params_.subsampling == 1 ||
cam_params_.subsampling == 2 ||
cam_params_.subsampling == 4 ||
cam_params_.subsampling == 8 ||
cam_params_.subsampling == 16)) {
WARN_STREAM("Invalid or unsupported requested subsampling rate for [" <<
cam_name_ << "]: " << cam_params_.subsampling <<
"; using current rate: " << prevCamParams.subsampling);
cam_params_.subsampling = prevCamParams.subsampling;
} else {
hasNewParams = true;
}
}
} else {
local_nh.setParam("subsampling", cam_params_.subsampling);
}
if (local_nh.hasParam("auto_gain")) {
local_nh.getParam("auto_gain", cam_params_.auto_gain);
if (cam_params_.auto_gain != prevCamParams.auto_gain) {
hasNewParams = true;
}
} else {
local_nh.setParam("auto_gain", cam_params_.auto_gain);
}
if (local_nh.hasParam("master_gain")) {
local_nh.getParam("master_gain", cam_params_.master_gain);
if (cam_params_.master_gain != prevCamParams.master_gain) {
if (cam_params_.master_gain < 0 || cam_params_.master_gain > 100) {
WARN_STREAM("Invalid master gain for [" << cam_name_ << "]: " <<
cam_params_.master_gain << "; using current master gain: " << prevCamParams.master_gain);
cam_params_.master_gain = prevCamParams.master_gain;
} else {
hasNewParams = true;
}
}
} else {
local_nh.setParam("master_gain", cam_params_.master_gain);
}
if (local_nh.hasParam("red_gain")) {
local_nh.getParam("red_gain", cam_params_.red_gain);
if (cam_params_.red_gain != prevCamParams.red_gain) {
if (cam_params_.red_gain < 0 || cam_params_.red_gain > 100) {
WARN_STREAM("Invalid red gain for [" << cam_name_ << "]: " <<
cam_params_.red_gain << "; using current red gain: " << prevCamParams.red_gain);
cam_params_.red_gain = prevCamParams.red_gain;
} else {
hasNewParams = true;
}
}
} else {
local_nh.setParam("red_gain", cam_params_.red_gain);
}
if (local_nh.hasParam("green_gain")) {
local_nh.getParam("green_gain", cam_params_.green_gain);
if (cam_params_.green_gain != prevCamParams.green_gain) {
if (cam_params_.green_gain < 0 || cam_params_.green_gain > 100) {
WARN_STREAM("Invalid green gain for [" << cam_name_ << "]: " <<
cam_params_.green_gain << "; using current green gain: " << prevCamParams.green_gain);
cam_params_.green_gain = prevCamParams.green_gain;
} else {
hasNewParams = true;
}
}
} else {
local_nh.setParam("green_gain", cam_params_.green_gain);
}
if (local_nh.hasParam("blue_gain")) {
local_nh.getParam("blue_gain", cam_params_.blue_gain);
if (cam_params_.blue_gain != prevCamParams.blue_gain) {
if (cam_params_.blue_gain < 0 || cam_params_.blue_gain > 100) {
WARN_STREAM("Invalid blue gain for [" << cam_name_ << "]: " <<
cam_params_.blue_gain << "; using current blue gain: " << prevCamParams.blue_gain);
cam_params_.blue_gain = prevCamParams.blue_gain;
} else {
hasNewParams = true;
}
}
} else {
local_nh.setParam("blue_gain", cam_params_.blue_gain);
}
if (local_nh.hasParam("gain_boost")) {
local_nh.getParam("gain_boost", cam_params_.gain_boost);
if (cam_params_.gain_boost != prevCamParams.gain_boost) {
hasNewParams = true;
}
} else {
local_nh.setParam("gain_boost", cam_params_.gain_boost);
}
if (local_nh.hasParam("software_gamma")) {
local_nh.getParam("software_gamma", cam_params_.software_gamma);
if (cam_params_.software_gamma != prevCamParams.software_gamma) {
hasNewParams = true;
}
}
if (local_nh.hasParam("auto_exposure")) {
local_nh.getParam("auto_exposure", cam_params_.auto_exposure);
if (cam_params_.auto_exposure != prevCamParams.auto_exposure) {
hasNewParams = true;
}
} else {
local_nh.setParam("auto_exposure", cam_params_.auto_exposure);
}
if (local_nh.hasParam("auto_exposure_reference")) {
local_nh.getParam("auto_exposure_reference", cam_params_.auto_exposure_reference);
if (cam_params_.auto_exposure_reference != prevCamParams.auto_exposure_reference) {
hasNewParams = true;
}
} else {
local_nh.setParam("auto_exposure_reference", cam_params_.auto_exposure_reference);
}
if (local_nh.hasParam("exposure")) {
local_nh.getParam("exposure", cam_params_.exposure);
if (cam_params_.exposure != prevCamParams.exposure) {
if (cam_params_.exposure < 0.0) {
WARN_STREAM("Invalid requested exposure: " << cam_params_.exposure <<
"; using current exposure: " << prevCamParams.exposure);
cam_params_.exposure = prevCamParams.exposure;
} else {
hasNewParams = true;
}
}
} else {
local_nh.setParam("exposure", cam_params_.exposure);
}
if (local_nh.hasParam("auto_white_balance")) {
local_nh.getParam("auto_white_balance", cam_params_.auto_white_balance);
if (cam_params_.auto_white_balance != prevCamParams.auto_white_balance) {
hasNewParams = true;
}
} else {
local_nh.setParam("auto_white_balance", cam_params_.auto_white_balance);
}
if (local_nh.hasParam("white_balance_red_offset")) {
local_nh.getParam("white_balance_red_offset", cam_params_.white_balance_red_offset);
if (cam_params_.white_balance_red_offset != prevCamParams.white_balance_red_offset) {
if (cam_params_.white_balance_red_offset < -50 || cam_params_.white_balance_red_offset > 50) {
WARN_STREAM("Invalid white balance red offset for [" << cam_name_ << "]: " <<
cam_params_.white_balance_red_offset <<
"; using current white balance red offset: " << prevCamParams.white_balance_red_offset);
cam_params_.white_balance_red_offset = prevCamParams.white_balance_red_offset;
} else {
hasNewParams = true;
}
}
} else {
local_nh.setParam("white_balance_red_offset", cam_params_.white_balance_red_offset);
}
if (local_nh.hasParam("white_balance_blue_offset")) {
local_nh.getParam("white_balance_blue_offset", cam_params_.white_balance_blue_offset);
if (cam_params_.white_balance_blue_offset != prevCamParams.white_balance_blue_offset) {
if (cam_params_.white_balance_blue_offset < -50 || cam_params_.white_balance_blue_offset > 50) {
WARN_STREAM("Invalid white balance blue offset for [" << cam_name_ << "]: " <<
cam_params_.white_balance_blue_offset <<
"; using current white balance blue offset: " << prevCamParams.white_balance_blue_offset);
cam_params_.white_balance_blue_offset = prevCamParams.white_balance_blue_offset;
} else {
hasNewParams = true;
}
}
} else {
local_nh.setParam("white_balance_blue_offset", cam_params_.white_balance_blue_offset);
}
if (local_nh.hasParam("ext_trigger_mode")) {
local_nh.getParam("ext_trigger_mode", cam_params_.ext_trigger_mode);
// NOTE: no need to set any parameters, since external trigger / live-run
// modes come into effect during frame grab loop, which is assumed
// to not having been initialized yet
} else {
local_nh.setParam("ext_trigger_mode", cam_params_.ext_trigger_mode);
}
if (local_nh.hasParam("flash_delay")) {
local_nh.getParam("flash_delay", cam_params_.flash_delay);
// NOTE: no need to set any parameters, since flash delay comes into
// effect during frame grab loop, which is assumed to not having been
// initialized yet
} else {
local_nh.setParam("flash_delay", cam_params_.flash_delay);
}
if (local_nh.hasParam("flash_duration")) {
local_nh.getParam("flash_duration", cam_params_.flash_duration);
if (cam_params_.flash_duration < 0) {
WARN_STREAM("Invalid flash duration for [" << cam_name_ << "]: " <<
cam_params_.flash_duration <<
"; using current flash duration: " << prevCamParams.flash_duration);
cam_params_.flash_duration = prevCamParams.flash_duration;
}
// NOTE: no need to set any parameters, since flash duration comes into
// effect during frame grab loop, which is assumed to not having been
// initialized yet
} else {
local_nh.setParam("flash_duration", cam_params_.flash_duration);
}
if (local_nh.hasParam("gpio1")) {
local_nh.getParam("gpio1", cam_params_.gpio1);
if (cam_params_.gpio1 != prevCamParams.gpio1) {hasNewParams = true;}
} else {
local_nh.setParam("gpio1", cam_params_.gpio1);
}
if (local_nh.hasParam("gpio2")) {
local_nh.getParam("gpio2", cam_params_.gpio2);
if (cam_params_.gpio2 != prevCamParams.gpio2) {hasNewParams = true;}
} else {
local_nh.setParam("gpio2", cam_params_.gpio2);
}
if (local_nh.hasParam("pwm_freq")) {
local_nh.getParam("pwm_freq", cam_params_.pwm_freq);
if (cam_params_.pwm_freq != prevCamParams.pwm_freq) {hasNewParams = true;}
} else {
local_nh.setParam("pwm_freq", cam_params_.pwm_freq);
}
if (local_nh.hasParam("pwm_duty_cycle")) {
local_nh.getParam("pwm_duty_cycle", cam_params_.pwm_duty_cycle);
if (cam_params_.pwm_duty_cycle != prevCamParams.pwm_duty_cycle) {hasNewParams = true;}
} else {
local_nh.setParam("pwm_duty_cycle", cam_params_.pwm_duty_cycle);
}
if (local_nh.hasParam("auto_frame_rate")) {
local_nh.getParam("auto_frame_rate", cam_params_.auto_frame_rate);
if (cam_params_.auto_frame_rate != prevCamParams.auto_frame_rate) {
hasNewParams = true;
}
} else {
local_nh.setParam("auto_frame_rate", cam_params_.auto_frame_rate);
}
if (local_nh.hasParam("frame_rate")) {
local_nh.getParam("frame_rate", cam_params_.frame_rate);
if (cam_params_.frame_rate != prevCamParams.frame_rate) {
if (cam_params_.frame_rate <= 0.0) {
WARN_STREAM("Invalid requested frame rate for [" << cam_name_ << "]: " <<
cam_params_.frame_rate <<
"; using current frame rate: " << prevCamParams.frame_rate);
cam_params_.frame_rate = prevCamParams.frame_rate;
} else {
hasNewParams = true;
}
}
} else {
local_nh.setParam("frame_rate", cam_params_.frame_rate);
}
if (local_nh.hasParam("output_rate")) {
local_nh.getParam("output_rate", cam_params_.output_rate);
if (cam_params_.output_rate < 0.0) {
WARN_STREAM("Invalid requested output rate for [" << cam_name_ << "]: " <<
cam_params_.output_rate <<
"; disable publisher throttling by default");
cam_params_.output_rate = 0;
} else {
cam_params_.output_rate = std::min(cam_params_.frame_rate, cam_params_.output_rate);
// hasNewParams = true; // No need to re-allocate buffer memory or reconfigure camera parameters
}
} else {
local_nh.setParam("output_rate", cam_params_.output_rate);
}
if (local_nh.hasParam("pixel_clock")) {
local_nh.getParam("pixel_clock", cam_params_.pixel_clock);
if (cam_params_.pixel_clock != prevCamParams.pixel_clock) {
if (cam_params_.pixel_clock < 0) {
WARN_STREAM("Invalid requested pixel clock for [" << cam_name_ << "]: " <<
cam_params_.pixel_clock <<
"; using current pixel clock: " << prevCamParams.pixel_clock);
cam_params_.pixel_clock = prevCamParams.pixel_clock;
} else {
hasNewParams = true;
}
}
} else {
local_nh.setParam("pixel_clock", cam_params_.pixel_clock);
}
if (local_nh.hasParam("flip_upd")) {
local_nh.getParam("flip_upd", cam_params_.flip_upd);
if (cam_params_.flip_upd != prevCamParams.flip_upd) {
hasNewParams = true;
}
} else {
local_nh.setParam("flip_upd", cam_params_.flip_upd);
}
if (local_nh.hasParam("flip_lr")) {
local_nh.getParam("flip_lr", cam_params_.flip_lr);
if (cam_params_.flip_lr != prevCamParams.flip_lr) {
hasNewParams = true;
}
} else {
local_nh.setParam("flip_lr", cam_params_.flip_lr);
}
if (hasNewParams) {
// Configure color mode, resolution, and subsampling rate
// NOTE: this batch of configurations are mandatory, to ensure proper allocation of local frame buffer
if ((is_err = setColorMode(cam_params_.color_mode, false)) != IS_SUCCESS) return is_err;
if ((is_err = setSubsampling(cam_params_.subsampling, false)) != IS_SUCCESS) return is_err;
if ((is_err = setBinning(cam_params_.binning, false)) != IS_SUCCESS) return is_err;
if ((is_err = setResolution(cam_params_.image_width, cam_params_.image_height,
cam_params_.image_left, cam_params_.image_top, false)) != IS_SUCCESS) return is_err;
if ((is_err = setSensorScaling(cam_params_.sensor_scaling, false)) != IS_SUCCESS) return is_err;
// Force synchronize settings and re-allocate frame buffer for redundancy
// NOTE: although this might not be needed, assume that parseROSParams()
// is called only once per nodelet, thus ignore cost
if ((is_err = syncCamConfig()) != IS_SUCCESS) return is_err;
// Check for mutual exclusivity among requested sensor parameters
if (!cam_params_.auto_exposure) { // Auto frame rate requires auto shutter
cam_params_.auto_frame_rate = false;
}
if (cam_params_.auto_frame_rate) { // Auto frame rate has precedence over auto gain
cam_params_.auto_gain = false;
}
// Configure camera sensor parameters
// NOTE: failing to configure certain parameters may or may not cause camera to fail;
// cuurently their failures are treated as non-critical
//#define noop return is_err
#define noop (void)0
if ((is_err = setGain(cam_params_.auto_gain, cam_params_.master_gain,
cam_params_.red_gain, cam_params_.green_gain,
cam_params_.blue_gain, cam_params_.gain_boost)) != IS_SUCCESS) noop;
if ((is_err = setSoftwareGamma(cam_params_.software_gamma)) != IS_SUCCESS) noop;
if ((is_err = setPixelClockRate(cam_params_.pixel_clock)) != IS_SUCCESS) return is_err;
if ((is_err = setFrameRate(cam_params_.auto_frame_rate, cam_params_.frame_rate)) != IS_SUCCESS) return is_err;
if ((is_err = setExposure(cam_params_.auto_exposure, cam_params_.auto_exposure_reference, cam_params_.exposure)) != IS_SUCCESS) noop;
if ((is_err = setWhiteBalance(cam_params_.auto_white_balance, cam_params_.white_balance_red_offset,
cam_params_.white_balance_blue_offset)) != IS_SUCCESS) noop;
if ((is_err = setGpioMode(1, cam_params_.gpio1, cam_params_.pwm_freq, cam_params_.pwm_duty_cycle)) != IS_SUCCESS) noop;
if ((is_err = setGpioMode(2, cam_params_.gpio2, cam_params_.pwm_freq, cam_params_.pwm_duty_cycle)) != IS_SUCCESS) noop;
if ((is_err = setMirrorUpsideDown(cam_params_.flip_upd)) != IS_SUCCESS) noop;
if ((is_err = setMirrorLeftRight(cam_params_.flip_lr)) != IS_SUCCESS) noop;
#undef noop
}
DEBUG_STREAM("Successfully applied settings from ROS params to [" << cam_name_ << "]");
return is_err;
}
void UEyeCamNodelet::configCallback(ueye_cam::UEyeCamConfig& config, uint32_t level) {
if (!isConnected()) return;
// See if frame grabber needs to be restarted
bool restartFrameGrabber = false;
bool needToReallocateBuffer = false;
if (level == RECONFIGURE_STOP && frame_grab_alive_) {
restartFrameGrabber = true;
stopFrameGrabber();
}
// Configure color mode, resolution, and subsampling rate
if (config.color_mode != cam_params_.color_mode) {
needToReallocateBuffer = true;
if (setColorMode(config.color_mode, false) != IS_SUCCESS) return;
}
if (config.image_width != cam_params_.image_width ||
config.image_height != cam_params_.image_height ||
config.image_left != cam_params_.image_left ||
config.image_top != cam_params_.image_top) {
needToReallocateBuffer = true;
if (setResolution(config.image_width, config.image_height,
config.image_left, config.image_top, false) != IS_SUCCESS) {
// Attempt to restore previous (working) resolution
config.image_width = cam_params_.image_width;
config.image_height = cam_params_.image_height;
config.image_left = cam_params_.image_left;
config.image_top = cam_params_.image_top;
if (setResolution(config.image_width, config.image_height,
config.image_left, config.image_top, false) != IS_SUCCESS) return;
}
}
if (config.subsampling != cam_params_.subsampling) {
needToReallocateBuffer = true;
if (setSubsampling(config.subsampling, false) != IS_SUCCESS) return;
}
if (config.binning != cam_params_.binning) {
needToReallocateBuffer = true;
if (setBinning(config.binning, false) != IS_SUCCESS) return;
}
if (config.sensor_scaling != cam_params_.sensor_scaling) {
needToReallocateBuffer = true;
if (setSensorScaling(config.sensor_scaling, false) != IS_SUCCESS) return;
}
// Reallocate internal camera buffer, and synchronize both non-ROS and ROS settings
// for redundancy
if (needToReallocateBuffer) {
if (syncCamConfig() != IS_SUCCESS) return;
needToReallocateBuffer = false;
}
// Check for mutual exclusivity among requested sensor parameters
if (!config.auto_exposure) { // Auto frame rate requires auto shutter
config.auto_frame_rate = false;
}
if (config.auto_frame_rate) { // Auto frame rate has precedence over auto gain
config.auto_gain = false;
}
// Configure camera sensor parameters
if (config.auto_gain != cam_params_.auto_gain ||
config.master_gain != cam_params_.master_gain ||
config.red_gain != cam_params_.red_gain ||
config.green_gain != cam_params_.green_gain ||
config.blue_gain != cam_params_.blue_gain ||
config.gain_boost != cam_params_.gain_boost) {
// If any of the manual gain params change, then automatically toggle off auto_gain
if (config.master_gain != cam_params_.master_gain ||
config.red_gain != cam_params_.red_gain ||
config.green_gain != cam_params_.green_gain ||
config.blue_gain != cam_params_.blue_gain ||
config.gain_boost != cam_params_.gain_boost) {
config.auto_gain = false;
}
if (setGain(config.auto_gain, config.master_gain,
config.red_gain, config.green_gain,
config.blue_gain, config.gain_boost) != IS_SUCCESS) return;
}
if (config.software_gamma != cam_params_.software_gamma) {
if (setSoftwareGamma(config.software_gamma) != IS_SUCCESS) return;
}
if (config.pixel_clock != cam_params_.pixel_clock) {
if (setPixelClockRate(config.pixel_clock) != IS_SUCCESS) return;
}
if (config.auto_frame_rate != cam_params_.auto_frame_rate ||
config.frame_rate != cam_params_.frame_rate) {
if (setFrameRate(config.auto_frame_rate, config.frame_rate) != IS_SUCCESS) return;
}
if (config.output_rate != cam_params_.output_rate) {
if (!config.auto_frame_rate) {
config.output_rate = std::min(config.output_rate, config.frame_rate);
} // else, auto-fps is enabled, so don't bother checking validity of user-specified config.output_rate
// Reset reference time for publisher throttle
output_rate_mutex_.lock();
init_publish_time_ = ros::Time(0);
prev_output_frame_idx_ = 0;
output_rate_mutex_.unlock();
}
if (config.auto_exposure != cam_params_.auto_exposure ||
config.auto_exposure_reference != cam_params_.auto_exposure_reference ||
config.exposure != cam_params_.exposure) {
if (setExposure(config.auto_exposure, config.auto_exposure_reference, config.exposure) != IS_SUCCESS) return;
}
if (config.auto_white_balance != cam_params_.auto_white_balance ||
config.white_balance_red_offset != cam_params_.white_balance_red_offset ||
config.white_balance_blue_offset != cam_params_.white_balance_blue_offset) {
if (setWhiteBalance(config.auto_white_balance, config.white_balance_red_offset,
config.white_balance_blue_offset) != IS_SUCCESS) return;
}
if (config.flip_upd != cam_params_.flip_upd) {
if (setMirrorUpsideDown(config.flip_upd) != IS_SUCCESS) return;
}
if (config.flip_lr != cam_params_.flip_lr) {
if (setMirrorLeftRight(config.flip_lr) != IS_SUCCESS) return;
}
// NOTE: nothing needs to be done for config.ext_trigger_mode, since frame grabber loop will re-initialize to the right setting
if (config.flash_delay != cam_params_.flash_delay ||
config.flash_duration != cam_params_.flash_duration) {
// NOTE: need to copy flash parameters to local copies since
// cam_params_.flash_duration is type int, and also sizeof(int)
// may not equal to sizeof(INT) / sizeof(UINT)
INT flash_delay = config.flash_delay;
UINT flash_duration = static_cast<UINT>(config.flash_duration);
setFlashParams(flash_delay, flash_duration);
// Copy back actual flash parameter values that were set
config.flash_delay = flash_delay;
config.flash_duration = static_cast<int>(flash_duration);
}
// Change gpio if mode has changed OR if mode is pwm and pwm settings have been changed
if ((config.gpio1 != cam_params_.gpio1) ||
(config.gpio1 == 4 && ((config.pwm_freq != cam_params_.pwm_freq) || (config.pwm_duty_cycle != cam_params_.pwm_duty_cycle)))) {
if (setGpioMode(1, config.gpio1, config.pwm_freq, config.pwm_duty_cycle) != IS_SUCCESS) return;
}
if ((config.gpio2 != cam_params_.gpio2) ||
(config.gpio2 == 4 && ((config.pwm_freq != cam_params_.pwm_freq) || (config.pwm_duty_cycle != cam_params_.pwm_duty_cycle)))) {
if (setGpioMode(2, config.gpio2, config.pwm_freq, config.pwm_duty_cycle) != IS_SUCCESS) return;
}
// Update local copy of parameter set to newly updated set
cam_params_ = config;
// Restart frame grabber if needed
cfg_sync_requested_ = true;
if (restartFrameGrabber) {
startFrameGrabber();
}
DEBUG_STREAM("Successfully applied settings from dyncfg to [" << cam_name_ << "]");
}
INT UEyeCamNodelet::syncCamConfig(string dft_mode_str) {
INT is_err;
if ((is_err = UEyeCamDriver::syncCamConfig(dft_mode_str)) != IS_SUCCESS) return is_err;
// Update ROS color mode string
cam_params_.color_mode = colormode2name(is_SetColorMode(cam_handle_, IS_GET_COLOR_MODE));
if (cam_params_.color_mode.empty()) {
ERROR_STREAM("Force-updating to default color mode for [" << cam_name_ << "]: " <<
dft_mode_str << "\n(THIS IS A CODING ERROR, PLEASE CONTACT PACKAGE AUTHOR)");
cam_params_.color_mode = dft_mode_str;
setColorMode(cam_params_.color_mode);
}
// Copy internal settings to ROS dynamic configure settings
cam_params_.image_width = cam_aoi_.s32Width; // Technically, these are width and height for the
cam_params_.image_height = cam_aoi_.s32Height; // sensor's Area of Interest, and not of the image
if (cam_params_.image_left >= 0) cam_params_.image_left = cam_aoi_.s32X; // TODO: 1 ideally want to ensure that aoi top-left does correspond to centering
if (cam_params_.image_top >= 0) cam_params_.image_top = cam_aoi_.s32Y;
cam_params_.subsampling = static_cast<int>(cam_subsampling_rate_);
cam_params_.binning = static_cast<int>(cam_binning_rate_);
cam_params_.sensor_scaling = cam_sensor_scaling_rate_;
//cfg_sync_requested_ = true; // WARNING: assume that dyncfg client may want to override current settings
// (Re-)populate ROS image message
ros_image_.header.frame_id = frame_name_;
// NOTE: .height, .width, .encoding, .step and .data determined in fillImgMsg();
// .is_bigendian determined in constructor
return is_err;
}
INT UEyeCamNodelet::queryCamParams() {
INT is_err = IS_SUCCESS;
INT query;
double pval1, pval2;
// NOTE: assume that color mode, bits per pixel, area of interest info, resolution,
// sensor scaling rate, subsampling rate, and binning rate have already
// been synchronized by syncCamConfig()
if ((is_err = is_SetAutoParameter(cam_handle_,
IS_GET_ENABLE_AUTO_SENSOR_GAIN, &pval1, &pval2)) != IS_SUCCESS &&
(is_err = is_SetAutoParameter(cam_handle_,
IS_GET_ENABLE_AUTO_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
ERROR_STREAM("Failed to query auto gain mode for UEye camera '" <<
cam_name_ << "' (" << err2str(is_err) << ")");
return is_err;
}
cam_params_.auto_gain = (pval1 != 0);
cam_params_.master_gain = is_SetHardwareGain(cam_handle_, IS_GET_MASTER_GAIN,
IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
cam_params_.red_gain = is_SetHardwareGain(cam_handle_, IS_GET_RED_GAIN,
IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
cam_params_.green_gain = is_SetHardwareGain(cam_handle_, IS_GET_GREEN_GAIN,
IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
cam_params_.blue_gain = is_SetHardwareGain(cam_handle_, IS_GET_BLUE_GAIN,
IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
query = is_SetGainBoost(cam_handle_, IS_GET_SUPPORTED_GAINBOOST);
if(query == IS_SET_GAINBOOST_ON) {
query = is_SetGainBoost(cam_handle_, IS_GET_GAINBOOST);
if (query == IS_SET_GAINBOOST_ON) {
cam_params_.gain_boost = true;
} else if (query == IS_SET_GAINBOOST_OFF) {
cam_params_.gain_boost = false;
} else {
ERROR_STREAM("Failed to query gain boost for [" << cam_name_ <<
"] (" << err2str(query) << ")");
return query;
}
} else {
cam_params_.gain_boost = false;
}
if ((is_err = is_Gamma(cam_handle_, IS_GAMMA_CMD_GET, (void*) &cam_params_.software_gamma,
sizeof(cam_params_.software_gamma))) != IS_SUCCESS) {
ERROR_STREAM("Failed to query software gamma value for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
if ((is_err = is_SetAutoParameter(cam_handle_,
IS_GET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2)) != IS_SUCCESS &&
(is_err = is_SetAutoParameter(cam_handle_,
IS_GET_ENABLE_AUTO_SHUTTER, &pval1, &pval2)) != IS_SUCCESS) {
ERROR_STREAM("Failed to query auto shutter mode for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
cam_params_.auto_exposure = (pval1 != 0);
if ((is_err = is_SetAutoParameter (cam_handle_, IS_GET_AUTO_REFERENCE,
&cam_params_.auto_exposure_reference, 0)) != IS_SUCCESS) {
ERROR_STREAM("Failed to query exposure reference value for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
}
if ((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_GET_EXPOSURE,
&cam_params_.exposure, sizeof(cam_params_.exposure))) != IS_SUCCESS) {
ERROR_STREAM("Failed to query exposure timing for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
if ((is_err = is_SetAutoParameter(cam_handle_,
IS_GET_ENABLE_AUTO_SENSOR_WHITEBALANCE, &pval1, &pval2)) != IS_SUCCESS &&
(is_err = is_SetAutoParameter(cam_handle_,
IS_GET_ENABLE_AUTO_WHITEBALANCE, &pval1, &pval2)) != IS_SUCCESS) {
ERROR_STREAM("Failed to query auto white balance mode for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
cam_params_.auto_white_balance = (pval1 != 0);
if ((is_err = is_SetAutoParameter(cam_handle_,
IS_GET_AUTO_WB_OFFSET, &pval1, &pval2)) != IS_SUCCESS) {
ERROR_STREAM("Failed to query auto white balance red/blue channel offsets for [" <<
cam_name_ << "] (" << err2str(is_err) << ")");
return is_err;
}
cam_params_.white_balance_red_offset = static_cast<int>(pval1);
cam_params_.white_balance_blue_offset = static_cast<int>(pval2);
IO_FLASH_PARAMS currFlashParams;
if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_GET_PARAMS,
(void*) &currFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
ERROR_STREAM("Could not retrieve current flash parameter info for [" <<
cam_name_ << "] (" << err2str(is_err) << ")");
return is_err;
}
cam_params_.flash_delay = currFlashParams.s32Delay;
cam_params_.flash_duration = static_cast<int>(currFlashParams.u32Duration);
if ((is_err = is_SetAutoParameter(cam_handle_,
IS_GET_ENABLE_AUTO_SENSOR_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS &&
(is_err = is_SetAutoParameter(cam_handle_,
IS_GET_ENABLE_AUTO_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS) {
ERROR_STREAM("Failed to query auto frame rate mode for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
cam_params_.auto_frame_rate = (pval1 != 0);
if ((is_err = is_SetFrameRate(cam_handle_, IS_GET_FRAMERATE, &cam_params_.frame_rate)) != IS_SUCCESS) {
ERROR_STREAM("Failed to query frame rate for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
UINT currPixelClock;
if ((is_err = is_PixelClock(cam_handle_, IS_PIXELCLOCK_CMD_GET,
(void*) &currPixelClock, sizeof(currPixelClock))) != IS_SUCCESS) {
ERROR_STREAM("Failed to query pixel clock rate for [" << cam_name_ <<
"] (" << err2str(is_err) << ")");
return is_err;
}
cam_params_.pixel_clock = static_cast<int>(currPixelClock);
INT currROP = is_SetRopEffect(cam_handle_, IS_GET_ROP_EFFECT, 0, 0);
cam_params_.flip_upd = ((currROP & IS_SET_ROP_MIRROR_UPDOWN) == IS_SET_ROP_MIRROR_UPDOWN);
cam_params_.flip_lr = ((currROP & IS_SET_ROP_MIRROR_LEFTRIGHT) == IS_SET_ROP_MIRROR_LEFTRIGHT);
// NOTE: do not need to (re-)populate ROS image message, since assume that
// syncCamConfig() was previously called
DEBUG_STREAM("Successfully queries parameters from [" << cam_name_ << "]");
return is_err;
}
INT UEyeCamNodelet::connectCam() {
INT is_err = IS_SUCCESS;
if ((is_err = UEyeCamDriver::connectCam()) != IS_SUCCESS) return is_err;
// (Attempt to) load UEye camera parameter configuration file
if (cam_params_filename_.length() <= 0) { // Try to use default filename if not specified otherwise
std::string cam_params_filename_fallback = string(getenv("HOME")) + "/.ros/camera_conf/" + cam_name_ + ".ini";
if (access( cam_params_filename_fallback.c_str(), F_OK ) != -1 ) { cam_params_filename_=cam_params_filename_fallback;}
}
if (cam_params_filename_.length() > 0) {
if ((is_err = loadCamConfig(cam_params_filename_)) != IS_SUCCESS) return is_err;
}
// Query existing configuration parameters from camera
if ((is_err = queryCamParams()) != IS_SUCCESS) return is_err;
// Parse and load ROS camera settings
if ((is_err = parseROSParams(getPrivateNodeHandle())) != IS_SUCCESS) return is_err;
return IS_SUCCESS;
}
INT UEyeCamNodelet::disconnectCam() {
INT is_err = IS_SUCCESS;