forked from srv/avt_vimba_camera
-
Notifications
You must be signed in to change notification settings - Fork 43
/
avt_vimba_camera.cpp
1197 lines (1108 loc) · 37.8 KB
/
avt_vimba_camera.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
/// Copyright (c) 2014,
/// Systems, Robotics and Vision Group
/// University of the Balearican Islands
/// 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.
/// * All advertising materials mentioning features or use of this software
/// must display the following acknowledgement:
/// This product includes software developed by
/// Systems, Robotics and Vision Group, Univ. of the Balearican Islands
/// * Neither the name of Systems, Robotics and Vision Group, University of
/// the Balearican Islands 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 <COPYRIGHT HOLDER> 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 <avt_vimba_camera/avt_vimba_camera.h>
#include <avt_vimba_camera/avt_vimba_api.h>
#include <ros/ros.h>
#include <signal.h>
#include <thread>
namespace avt_vimba_camera
{
static const char* AutoMode[] = { "Off", "Once", "Continuous" };
static const char* TriggerMode[] = { "Invalid", "Freerun", "FixedRate", "Software", "Line0", "Line1",
"Line2", "Line3", "Line4", "Action0", "Action1" };
static const char* AcquisitionMode[] = { "Continuous", "SingleFrame", "MultiFrame", "Recorder" };
static const char* PixelFormatMode[] = { "Mono8", "Mono10", "Mono10Packed", "Mono12",
"Mono12Packed", "BayerGR8", "BayerRG8", "BayerGB8",
"BayerBG8", "BayerGR10", "BayerRG10", "BayerGB10",
"BayerBG10", "BayerGR12", "BayerRG12", "BayerGB12",
"BayerBG12", "BayerGR10Packed", "BayerRG10Packed", "BayerGB10Packed",
"BayerBG10Packed", "BayerGR12Packed", "BayerRG12Packed", "BayerGB12Packed",
"BayerBG12Packed", "RGB8Packed", "BGR8Packed" };
static const char* BalanceRatioMode[] = { "Red", "Blue" };
static const char* FeatureDataType[] = { "Unknown", "int", "float", "enum", "string", "bool" };
static const char* State[] = { "Opening", "Idle", "Camera not found", "Format error", "Error", "Ok" };
static volatile int keepRunning = 1;
void intHandler(int dummy)
{
keepRunning = 0;
}
AvtVimbaCamera::AvtVimbaCamera() : AvtVimbaCamera(ros::this_node::getName().c_str())
{
}
AvtVimbaCamera::AvtVimbaCamera(const std::string& name)
{
// Init global variables
opened_ = false; // camera connected to the api
streaming_ = false; // capturing frames
on_init_ = true; // on initialization phase
name_ = name;
camera_state_ = OPENING;
updater_.setHardwareID("unknown");
updater_.add(name_, this, &AvtVimbaCamera::getCurrentState);
updater_.update();
}
void AvtVimbaCamera::start(const std::string& ip_str, const std::string& guid_str, const std::string& frame_id,
bool print_all_features)
{
if (opened_)
return;
frame_id_ = frame_id;
updater_.broadcast(0, "Starting device with IP:" + ip_str + " or GUID:" + guid_str);
// Determine which camera to use. Try IP first
if (!ip_str.empty())
{
diagnostic_msg_ = "Trying to open camera by IP: " + ip_str;
ROS_INFO_STREAM("Trying to open camera by IP: " << ip_str);
vimba_camera_ptr_ = openCamera(ip_str, print_all_features);
if (!vimba_camera_ptr_)
{
ROS_WARN("Camera pointer is empty. Returning...");
return;
}
updater_.setHardwareID(ip_str);
guid_ = ip_str;
// If both guid and IP are available, open by IP and check guid
if (!guid_str.empty())
{
std::string cam_guid_str;
vimba_camera_ptr_->GetSerialNumber(cam_guid_str);
if (!vimba_camera_ptr_)
{
ROS_WARN("Camera pointer is empty. Returning...");
return;
}
assert(cam_guid_str == guid_str);
updater_.setHardwareID(guid_str);
guid_ = guid_str;
diagnostic_msg_ = "GUID " + cam_guid_str + " matches for camera with IP: " + ip_str;
ROS_INFO_STREAM("GUID " << cam_guid_str << " matches for camera with IP: " << ip_str);
}
}
else if (!guid_str.empty())
{
// Only guid available
diagnostic_msg_ = "Trying to open camera by ID: " + guid_str;
ROS_INFO_STREAM("Trying to open camera by ID: " << guid_str);
vimba_camera_ptr_ = openCamera(guid_str, print_all_features);
updater_.setHardwareID(guid_str);
guid_ = guid_str;
}
else
{
// No identifying info (GUID and IP) are available
diagnostic_msg_ = "Can't connect to the camera: at least GUID or IP need to be set.";
ROS_ERROR("Can't connect to the camera: at least GUID or IP need to be set.");
camera_state_ = ERROR;
}
updater_.update();
getFeatureValue("GevTimestampTickFrequency", vimba_timestamp_tick_freq_);
// From the SynchronousGrab API example:
// TODO Set the GeV packet size to the highest possible value
VmbInterfaceType cam_int_type;
vimba_camera_ptr_->GetInterfaceType(cam_int_type);
if (cam_int_type == VmbInterfaceEthernet)
{
runCommand("GVSPAdjustPacketSize");
}
// Create a frame observer for this camera
SP_SET(frame_obs_ptr_,
new FrameObserver(vimba_camera_ptr_,
std::bind(&avt_vimba_camera::AvtVimbaCamera::frameCallback, this, std::placeholders::_1)));
camera_state_ = IDLE;
updater_.update();
}
void AvtVimbaCamera::stop()
{
if (!opened_)
return;
vimba_camera_ptr_->Close();
opened_ = false;
}
void AvtVimbaCamera::startImaging()
{
if (!streaming_)
{
// Start streaming
VmbErrorType err = vimba_camera_ptr_->StartContinuousImageAcquisition(3, IFrameObserverPtr(frame_obs_ptr_));
if (err == VmbErrorSuccess)
{
diagnostic_msg_ = "Starting continuous image acquisition";
ROS_INFO_STREAM("Starting continuous image acquisition ...");
streaming_ = true;
camera_state_ = OK;
}
else
{
diagnostic_msg_ = "Could not start continuous image acquisition. Error: " + api_.errorCodeToMessage(err);
ROS_ERROR_STREAM("Could not start continuous image acquisition. "
<< "\n Error: " << api_.errorCodeToMessage(err));
camera_state_ = ERROR;
}
}
else
{
ROS_WARN_STREAM("Start imaging called, but the camera is already imaging.");
}
updater_.update();
}
void AvtVimbaCamera::stopImaging()
{
if (streaming_ || on_init_)
{
VmbErrorType err = vimba_camera_ptr_->StopContinuousImageAcquisition();
if (err == VmbErrorSuccess)
{
diagnostic_msg_ = "Acquisition stopped";
ROS_INFO_STREAM("Acquisition stoppped ...");
streaming_ = false;
camera_state_ = IDLE;
}
else
{
diagnostic_msg_ = "Could not stop image acquisition. Error: " + api_.errorCodeToMessage(err);
ROS_ERROR_STREAM("Could not stop image acquisition."
<< "\n Error: " << api_.errorCodeToMessage(err));
camera_state_ = ERROR;
}
}
else
{
ROS_WARN_STREAM("Stop imaging called, but the camera is already stopped.");
}
updater_.update();
}
CameraPtr AvtVimbaCamera::openCamera(const std::string& id_str, bool print_all_features)
{
// Details: The ID might be one of the following:
// "IP:169.254.12.13",
// "MAC:000f31000001",
// or a plain serial number: "1234567890".
CameraPtr camera;
VimbaSystem& vimba_system(VimbaSystem::GetInstance());
// set handler to catch ctrl+c presses
sighandler_t oldHandler = signal(SIGINT, intHandler);
// get camera
VmbErrorType err = vimba_system.GetCameraByID(id_str.c_str(), camera);
while (err != VmbErrorSuccess)
{
if (keepRunning)
{
ROS_WARN_STREAM("Could not find camera using " << id_str << ". Retrying every two seconds ...");
ros::Duration(2.0).sleep();
err = vimba_system.GetCameraByID(id_str.c_str(), camera);
}
else
{
ROS_ERROR_STREAM("Could not find camera using " << id_str << "\n Error: " << api_.errorCodeToMessage(err));
camera_state_ = CAMERA_NOT_FOUND;
return camera;
}
}
// open camera
err = camera->Open(VmbAccessModeFull);
while (err != VmbErrorSuccess && keepRunning)
{
if (keepRunning)
{
ROS_WARN_STREAM("Could not open camera. Retrying every two seconds ...");
err = camera->Open(VmbAccessModeFull);
ros::Duration(2.0).sleep();
}
else
{
ROS_ERROR_STREAM("Could not open camera " << id_str << "\n Error: " << api_.errorCodeToMessage(err));
camera_state_ = CAMERA_NOT_FOUND;
return camera;
}
}
// set previous handler back
signal(SIGINT, oldHandler);
std::string cam_id, cam_name;
camera->GetID(cam_id);
camera->GetName(cam_name);
ROS_INFO_STREAM("Opened connection to camera named " << cam_name << " with ID " << cam_id);
ros::Duration(2.0).sleep();
if (print_all_features)
{
printAllCameraFeatures(camera);
}
opened_ = true;
camera_state_ = IDLE;
return camera;
}
void AvtVimbaCamera::frameCallback(const FramePtr vimba_frame_ptr)
{
std::unique_lock<std::mutex> lock(config_mutex_);
camera_state_ = OK;
diagnostic_msg_ = "Camera operating normally";
// Call the callback implemented by other classes
std::thread thread_callback = std::thread(userFrameCallback, vimba_frame_ptr);
thread_callback.join();
updater_.update();
}
double AvtVimbaCamera::getTimestamp()
{
double timestamp = -1.0;
if (runCommand("GevTimestampControlLatch"))
{
VmbInt64_t freq, ticks;
getFeatureValue("GevTimestampTickFrequency", freq);
getFeatureValue("GevTimestampValue", ticks);
timestamp = static_cast<double>(ticks) / static_cast<double>(freq);
}
return timestamp;
}
double AvtVimbaCamera::getDeviceTemp()
{
double temp = -1.0;
if (setFeatureValue("DeviceTemperatureSelector", "Main") == VmbErrorSuccess)
{
getFeatureValue("DeviceTemperature", temp);
}
return temp;
}
int AvtVimbaCamera::getSensorWidth()
{
int sensor_width;
if (getFeatureValue("SensorWidth", sensor_width))
{
return sensor_width;
}
else
{
return -1;
}
}
int AvtVimbaCamera::getSensorHeight()
{
int sensor_height;
if (getFeatureValue("SensorHeight", sensor_height))
{
return sensor_height;
}
else
{
return -1;
}
}
double AvtVimbaCamera::getTimestampRealTime(VmbUint64_t timestamp_ticks)
{
return (static_cast<double>(timestamp_ticks)) / (static_cast<double>(vimba_timestamp_tick_freq_));
}
// Template function to SET a feature value from the camera
template <typename T>
VmbErrorType AvtVimbaCamera::setFeatureValue(const std::string& feature_str, const T& val)
{
VmbErrorType err;
FeaturePtr vimba_feature_ptr;
err = vimba_camera_ptr_->GetFeatureByName(feature_str.c_str(), vimba_feature_ptr);
if (err == VmbErrorSuccess)
{
bool writable;
err = vimba_feature_ptr->IsWritable(writable);
if (err == VmbErrorSuccess)
{
if (writable)
{
ROS_DEBUG_STREAM("Setting feature " << feature_str << " value " << val);
VmbFeatureDataType data_type;
err = vimba_feature_ptr->GetDataType(data_type);
if (err == VmbErrorSuccess)
{
if (data_type == VmbFeatureDataEnum)
{
bool available;
err = vimba_feature_ptr->IsValueAvailable(val, available);
if (err == VmbErrorSuccess)
{
if (available)
{
err = vimba_feature_ptr->SetValue(val);
}
else
{
ROS_WARN_STREAM("Feature " << feature_str << " is available now.");
}
}
else
{
ROS_WARN_STREAM("Feature " << feature_str << ": value unavailable\n\tERROR "
<< api_.errorCodeToMessage(err));
}
}
else
{
err = vimba_feature_ptr->SetValue(val);
}
}
else
{
ROS_WARN_STREAM("Feature " << feature_str << ": Bad data type\n\tERROR " << api_.errorCodeToMessage(err));
}
}
else
{
ROS_WARN_STREAM("Feature " << feature_str << " is not writable.");
}
}
else
{
ROS_WARN_STREAM("Feature " << feature_str << ": ERROR " << api_.errorCodeToMessage(err));
}
}
else
{
ROS_WARN_STREAM("Could not get feature " << feature_str << ", your camera probably doesn't support it.");
}
return err;
}
// Template function to GET a feature value from the camera
template <typename T>
bool AvtVimbaCamera::getFeatureValue(const std::string& feature_str, T& val)
{
ROS_DEBUG_STREAM("Asking for feature " << feature_str);
VmbErrorType err;
FeaturePtr vimba_feature_ptr;
VmbFeatureDataType data_type;
err = vimba_camera_ptr_->GetFeatureByName(feature_str.c_str(), vimba_feature_ptr);
if (err == VmbErrorSuccess)
{
bool readable;
vimba_feature_ptr->IsReadable(readable);
if (readable)
{
vimba_feature_ptr->GetDataType(data_type);
if (err != VmbErrorSuccess)
{
std::cout << "[Could not get feature Data Type. Error code: " << err << "]" << std::endl;
}
else
{
switch (data_type)
{
case VmbFeatureDataBool:
bool bValue;
err = vimba_feature_ptr->GetValue(bValue);
if (err == VmbErrorSuccess)
{
val = static_cast<T>(bValue);
}
break;
case VmbFeatureDataFloat:
double fValue;
err = vimba_feature_ptr->GetValue(fValue);
if (err == VmbErrorSuccess)
{
val = static_cast<T>(fValue);
}
break;
case VmbFeatureDataInt:
VmbInt64_t nValue;
err = vimba_feature_ptr->GetValue(nValue);
if (err == VmbErrorSuccess)
{
val = static_cast<T>(nValue);
}
break;
default:
err = VmbErrorNotFound;
break;
}
if (err != VmbErrorSuccess)
{
ROS_WARN_STREAM("Could not get feature value. Error code: " << api_.errorCodeToMessage(err));
}
}
}
else
{
ROS_WARN_STREAM("Feature " << feature_str << " is not readable.");
}
}
else
{
ROS_WARN_STREAM("Could not get feature " << feature_str);
}
return (err == VmbErrorSuccess);
}
// Function to GET a feature value from the camera, overloaded to strings
bool AvtVimbaCamera::getFeatureValue(const std::string& feature_str, std::string& val)
{
ROS_DEBUG_STREAM("Asking for feature " << feature_str);
VmbErrorType err;
FeaturePtr vimba_feature_ptr;
VmbFeatureDataType data_type;
err = vimba_camera_ptr_->GetFeatureByName(feature_str.c_str(), vimba_feature_ptr);
if (err == VmbErrorSuccess)
{
bool readable;
vimba_feature_ptr->IsReadable(readable);
if (readable)
{
vimba_feature_ptr->GetDataType(data_type);
if (err != VmbErrorSuccess)
{
ROS_ERROR_STREAM("[Could not get feature Data Type. Error code: " << err << "]");
}
else
{
std::string strValue;
switch (data_type)
{
case VmbFeatureDataEnum:
err = vimba_feature_ptr->GetValue(strValue);
if (err == VmbErrorSuccess)
{
val = strValue;
}
break;
case VmbFeatureDataString:
err = vimba_feature_ptr->GetValue(strValue);
if (err == VmbErrorSuccess)
{
val = strValue;
}
break;
default:
err = VmbErrorNotFound;
break;
}
if (err != VmbErrorSuccess)
{
ROS_WARN_STREAM("Could not get feature value. Error code: " << api_.errorCodeToMessage(err));
}
}
}
else
{
ROS_WARN_STREAM("Feature " << feature_str << " is not readable.");
}
}
else
{
ROS_WARN_STREAM("Could not get feature " << feature_str);
}
return (err == VmbErrorSuccess);
}
// Tries to configure a camera feature.
// Updates the config value passed in if a different config is in use by the camera.
template <typename Vimba_Type, typename Std_Type>
void AvtVimbaCamera::configureFeature(const std::string& feature_str, const Vimba_Type& val_in, Std_Type& val_out)
{
Vimba_Type actual_value;
VmbErrorType return_value = setFeatureValue(feature_str, val_in);
if (return_value == VmbErrorSuccess || return_value == VmbErrorInvalidValue)
{
getFeatureValue(feature_str, actual_value);
if (val_in == actual_value)
{
ROS_INFO_STREAM(" - " << feature_str << " set to " << actual_value);
}
else
{
ROS_WARN_STREAM(" - Tried to set " << feature_str << " to " << val_in << " but the camera used " << actual_value
<< " instead");
val_out = static_cast<Std_Type>(actual_value);
}
}
else
{
val_out = static_cast<Std_Type>(val_in);
}
}
// Overloaded for strings, template specialization doesn't currently compile with GCC
void AvtVimbaCamera::configureFeature(const std::string& feature_str, const std::string& val_in, std::string& val_out)
{
std::string actual_value;
VmbErrorType return_value = setFeatureValue(feature_str, val_in.c_str());
if (return_value == VmbErrorSuccess || return_value == VmbErrorInvalidValue)
{
getFeatureValue(feature_str, actual_value);
if (val_in == actual_value)
{
ROS_INFO_STREAM(" - " << feature_str << " set to " << actual_value);
}
else
{
ROS_WARN_STREAM(" - Tried to set " << feature_str << " to " << val_in << " but the camera used " << actual_value
<< " instead");
val_out = actual_value;
}
}
else
{
val_out = val_in;
}
}
// Template function to RUN a command
bool AvtVimbaCamera::runCommand(const std::string& command_str)
{
FeaturePtr feature_ptr;
VmbErrorType err = vimba_camera_ptr_->GetFeatureByName(command_str.c_str(), feature_ptr);
if (err == VmbErrorSuccess)
{
err = feature_ptr->RunCommand();
if (err == VmbErrorSuccess)
{
bool is_command_done = false;
do
{
err = feature_ptr->IsCommandDone(is_command_done);
if (err != VmbErrorSuccess)
{
break;
}
ROS_DEBUG_STREAM_THROTTLE(1, "Waiting for command " << command_str.c_str() << "...");
} while (false == is_command_done);
ROS_DEBUG_STREAM("Command " << command_str.c_str() << " done!");
return true;
}
else
{
ROS_WARN_STREAM("Could not run command " << command_str << ". Error: " << api_.errorCodeToMessage(err));
return false;
}
}
else
{
ROS_WARN_STREAM("Could not get feature command " << command_str << ". Error: " << api_.errorCodeToMessage(err));
return false;
}
}
void AvtVimbaCamera::printAllCameraFeatures(const CameraPtr& camera)
{
VmbErrorType err;
FeaturePtrVector features;
// The static details of a feature
std::string strName; // The name of the feature
std::string strDisplayName; // The display name of the feature
std::string strDescription; // A long description of the feature
std::string strCategory; // A category to group features
std::string strSFNCNamespace; // The Std Feature Naming Convention namespace
std::string strUnit; // The measurement unit of the value
VmbFeatureDataType eType; // The data type of the feature
// The changeable value of a feature
VmbInt64_t nValue;
std::string strValue;
std::stringstream strError;
// Fetch all features of our cam
err = camera->GetFeatures(features);
if (err == VmbErrorSuccess)
{
// Query all static details as well as the value of
// all fetched features and print them out.
for (FeaturePtrVector::const_iterator iter = features.begin(); features.end() != iter; ++iter)
{
err = (*iter)->GetName(strName);
if (err != VmbErrorSuccess)
{
strError << "[Could not get feature Name. Error code: " << err << "]";
strName.assign(strError.str());
}
err = (*iter)->GetDisplayName(strDisplayName);
if (err != VmbErrorSuccess)
{
strError << "[Could not get feature Display Name. Error code: " << err << "]";
strDisplayName.assign(strError.str());
}
err = (*iter)->GetDescription(strDescription);
if (err != VmbErrorSuccess)
{
strError << "[Could not get feature Description. Error code: " << err << "]";
strDescription.assign(strError.str());
}
err = (*iter)->GetCategory(strCategory);
if (err != VmbErrorSuccess)
{
strError << "[Could not get feature Category. Error code: " << err << "]";
strCategory.assign(strError.str());
}
err = (*iter)->GetSFNCNamespace(strSFNCNamespace);
if (err != VmbErrorSuccess)
{
strError << "[Could not get feature SNFC Namespace. Error code: " << err << "]";
strSFNCNamespace.assign(strError.str());
}
err = (*iter)->GetUnit(strUnit);
if (err != VmbErrorSuccess)
{
strError << "[Could not get feature Unit. Error code: " << err << "]";
strUnit.assign(strError.str());
}
std::cout << "/// Feature Name: " << strName << std::endl;
std::cout << "/// Display Name: " << strDisplayName << std::endl;
std::cout << "/// Description: " << strDescription << std::endl;
std::cout << "/// SNFC Namespace: " << strSFNCNamespace << std::endl;
std::cout << "/// Unit: " << strUnit << std::endl;
std::cout << "/// Value: ";
err = (*iter)->GetDataType(eType);
if (err != VmbErrorSuccess)
{
std::cout << "[Could not get feature Data Type. Error code: " << err << "]" << std::endl;
}
else
{
switch (eType)
{
case VmbFeatureDataBool:
bool bValue;
err = (*iter)->GetValue(bValue);
if (err == VmbErrorSuccess)
{
std::cout << bValue << " (bool)" << std::endl;
}
break;
case VmbFeatureDataEnum:
err = (*iter)->GetValue(strValue);
if (err == VmbErrorSuccess)
{
std::cout << strValue << " (string enum)" << std::endl;
}
break;
case VmbFeatureDataFloat:
double fValue;
err = (*iter)->GetValue(fValue);
{
std::cout << fValue << " (float)" << std::endl;
}
break;
case VmbFeatureDataInt:
err = (*iter)->GetValue(nValue);
{
std::cout << nValue << " (int)" << std::endl;
}
break;
case VmbFeatureDataString:
err = (*iter)->GetValue(strValue);
{
std::cout << strValue << " (string)" << std::endl;
}
break;
case VmbFeatureDataCommand:
default:
std::cout << "[None]" << std::endl;
break;
}
if (err != VmbErrorSuccess)
{
std::cout << "Could not get feature value. Error code: " << err << std::endl;
}
}
std::cout << std::endl;
}
}
else
{
std::cout << "Could not get features. Error code: " << api_.errorCodeToMessage(err) << std::endl;
}
}
void AvtVimbaCamera::updateConfig(Config& config)
{
std::unique_lock<std::mutex> lock(config_mutex_);
if (streaming_)
{
stopImaging();
ros::Duration(0.5).sleep(); // sleep for half a second
}
if (on_init_)
{
config_ = config;
}
diagnostic_msg_ = "Updating configuration";
updateExposureConfig(config);
updateGainConfig(config);
updateWhiteBalanceConfig(config);
updateImageModeConfig(config);
updateROIConfig(config);
updateBandwidthConfig(config);
updateGPIOConfig(config);
updateUSBGPIOConfig(config);
updatePtpModeConfig(config);
updatePixelFormatConfig(config);
updateAcquisitionConfig(config);
updateIrisConfig(config);
config_ = config;
if (on_init_)
{
on_init_ = false;
}
startImaging();
}
/** Change the Trigger configuration */
void AvtVimbaCamera::updateAcquisitionConfig(Config& config)
{
if (on_init_)
{
ROS_INFO("Updating Acquisition and Trigger config:");
}
if (config.acquisition_mode != config_.acquisition_mode || on_init_)
{
configureFeature("AcquisitionMode", config.acquisition_mode, config.acquisition_mode);
}
if (config.acquisition_rate != config_.acquisition_rate || on_init_)
{
configureFeature("AcquisitionFrameRateAbs", static_cast<float>(config.acquisition_rate), config.acquisition_rate);
}
if (config.trigger_mode != config_.trigger_mode || on_init_)
{
configureFeature("TriggerMode", config.trigger_mode, config.trigger_mode);
}
if (config.trigger_selector != config_.trigger_selector || on_init_)
{
configureFeature("TriggerSelector", config.trigger_selector, config.trigger_selector);
}
if (config.trigger_source != config_.trigger_source || on_init_)
{
configureFeature("TriggerSource", config.trigger_source, config.trigger_source);
}
if (config.trigger_activation != config_.trigger_activation || on_init_)
{
configureFeature("TriggerActivation", config.trigger_activation, config.trigger_activation);
}
if (config.trigger_delay != config_.trigger_delay || on_init_)
{
configureFeature("TriggerDelayAbs", static_cast<float>(config.trigger_delay), config.trigger_delay);
}
if (config.action_device_key != config_.action_device_key || on_init_)
{
configureFeature("ActionDeviceKey", static_cast<VmbInt64_t>(config.action_device_key), config.action_device_key);
}
if (config.action_group_key != config_.action_group_key || on_init_)
{
configureFeature("ActionGroupKey", static_cast<VmbInt64_t>(config.action_group_key), config.action_group_key);
}
if (config.action_group_mask != config_.action_group_mask || on_init_)
{
configureFeature("ActionGroupMask", static_cast<VmbInt64_t>(config.action_group_mask), config.action_group_mask);
}
}
/* Update the Iris config */
void AvtVimbaCamera::updateIrisConfig(Config& config)
{
if (on_init_)
{
ROS_INFO("Updating Iris config:");
}
if (config.iris_auto_target != config_.iris_auto_target || on_init_)
{
configureFeature("IrisAutoTarget", static_cast<VmbInt64_t>(config.iris_auto_target), config.iris_auto_target);
}
if (config.iris_mode != config_.iris_mode || on_init_)
{
configureFeature("IrisMode", config.iris_mode, config.iris_mode);
}
if (config.iris_video_level_max != config_.iris_video_level_max || on_init_)
{
configureFeature("IrisVideoLevelMax", static_cast<VmbInt64_t>(config.iris_video_level_max),
config.iris_video_level_max);
}
if (config.iris_video_level_min != config_.iris_video_level_min || on_init_)
{
configureFeature("IrisVideoLevelMin", static_cast<VmbInt64_t>(config.iris_video_level_min),
config.iris_video_level_min);
}
}
/** Change the Exposure configuration */
void AvtVimbaCamera::updateExposureConfig(Config& config)
{
if (on_init_)
{
ROS_INFO("Updating Exposure config:");
}
if (config.exposure != config_.exposure || on_init_)
{
configureFeature("ExposureTimeAbs", static_cast<float>(config.exposure), config.exposure);
}
if (config.exposure_auto != config_.exposure_auto || on_init_)
{
configureFeature("ExposureAuto", config.exposure_auto, config.exposure_auto);
}
if (config.exposure_auto_alg != config_.exposure_auto_alg || on_init_)
{
configureFeature("ExposureAutoAlg", config.exposure_auto_alg, config.exposure_auto_alg);
}
if (config.exposure_auto_tol != config_.exposure_auto_tol || on_init_)
{
configureFeature("ExposureAutoAdjustTol", static_cast<VmbInt64_t>(config.exposure_auto_tol),
config.exposure_auto_tol);
}
if (config.exposure_auto_max != config_.exposure_auto_max || on_init_)
{
configureFeature("ExposureAutoMax", static_cast<VmbInt64_t>(config.exposure_auto_max), config.exposure_auto_max);
}
if (config.exposure_auto_min != config_.exposure_auto_min || on_init_)
{
configureFeature("ExposureAutoMin", static_cast<VmbInt64_t>(config.exposure_auto_min), config.exposure_auto_min);
}
if (config.exposure_auto_outliers != config_.exposure_auto_outliers || on_init_)
{
configureFeature("ExposureAutoOutliers", static_cast<VmbInt64_t>(config.exposure_auto_outliers),
config.exposure_auto_outliers);
}
if (config.exposure_auto_rate != config_.exposure_auto_rate || on_init_)
{
configureFeature("ExposureAutoRate", static_cast<VmbInt64_t>(config.exposure_auto_rate), config.exposure_auto_rate);
}
if (config.exposure_auto_target != config_.exposure_auto_target || on_init_)
{
configureFeature("ExposureAutoTarget", static_cast<VmbInt64_t>(config.exposure_auto_target),
config.exposure_auto_target);
}
}
/** Change the Gain configuration */
void AvtVimbaCamera::updateGainConfig(Config& config)
{
if (on_init_)
{
ROS_INFO("Updating Gain config:");
}
if (config.gain != config_.gain || on_init_)
{
configureFeature("Gain", static_cast<float>(config.gain), config.gain);
}
if (config.gain_auto != config_.gain_auto || on_init_)
{
configureFeature("GainAuto", config.gain_auto, config.gain_auto);
}
if (config.gain_auto_adjust_tol != config_.gain_auto_adjust_tol || on_init_)
{
configureFeature("GainAutoAdjustTol", static_cast<VmbInt64_t>(config.gain_auto_adjust_tol),
config.gain_auto_adjust_tol);
}
if (config.gain_auto_max != config_.gain_auto_max || on_init_)
{
configureFeature("GainAutoMax", static_cast<float>(config.gain_auto_max), config.gain_auto_max);
}
if (config.gain_auto_min != config_.gain_auto_min || on_init_)
{
configureFeature("GainAutoMin", static_cast<float>(config.gain_auto_min), config.gain_auto_min);
}
if (config.gain_auto_outliers != config_.gain_auto_outliers || on_init_)
{
configureFeature("GainAutoOutliers", static_cast<VmbInt64_t>(config.gain_auto_outliers), config.gain_auto_outliers);
}
if (config.gain_auto_rate != config_.gain_auto_rate || on_init_)
{
configureFeature("GainAutoRate", static_cast<VmbInt64_t>(config.gain_auto_rate), config.gain_auto_rate);
}
if (config.gain_auto_target != config_.gain_auto_target || on_init_)
{
configureFeature("GainAutoTarget", static_cast<VmbInt64_t>(config.gain_auto_target), config.gain_auto_target);
}
}
/** Change the White Balance configuration */
void AvtVimbaCamera::updateWhiteBalanceConfig(Config& config)
{
if (on_init_)
{