-
Notifications
You must be signed in to change notification settings - Fork 141
/
pylon_camera_base.hpp
2795 lines (2630 loc) · 89.7 KB
/
pylon_camera_base.hpp
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
/******************************************************************************
* Software License Agreement (BSD License)
*
* Copyright (C) 2016, Magazino GmbH. All rights reserved.
*
* Improved by drag and bot GmbH (www.dragandbot.com), 2019
*
* 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 names of Magazino GmbH 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.
*****************************************************************************/
#ifndef PYLON_CAMERA_INTERNAL_BASE_HPP_
#define PYLON_CAMERA_INTERNAL_BASE_HPP_
#include <cmath>
#include <string>
#include <vector>
#include <pylon_camera/internal/pylon_camera.h>
#include <pylon_camera/encoding_conversions.h>
#include <sensor_msgs/image_encodings.h>
namespace pylon_camera
{
template <typename CameraTraitT>
PylonCameraImpl<CameraTraitT>::PylonCameraImpl(Pylon::IPylonDevice* device) :
PylonCamera(),
cam_(new CBaslerInstantCameraT(device))
{}
template <typename CameraTraitT>
PylonCameraImpl<CameraTraitT>::~PylonCameraImpl()
{
delete cam_;
cam_ = nullptr;
if ( binary_exp_search_ )
{
delete binary_exp_search_;
binary_exp_search_ = nullptr;
}
}
template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::registerCameraConfiguration()
{
try
{
cam_->RegisterConfiguration(new Pylon::CSoftwareTriggerConfiguration,
Pylon::RegistrationMode_ReplaceAll,
Pylon::Cleanup_Delete);
return true;
}
catch ( const GenICam::GenericException &e )
{
ROS_ERROR_STREAM(e.GetDescription());
return false;
}
}
template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::openCamera()
{
try
{
cam_->Open();
return true;
}
catch ( const GenICam::GenericException &e )
{
ROS_ERROR_STREAM(e.GetDescription());
return false;
}
}
template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::isCamRemoved()
{
return cam_->IsCameraDeviceRemoved();
}
template <typename CameraTraitT>
size_t PylonCameraImpl<CameraTraitT>::currentOffsetX()
{
if ( GenApi::IsAvailable(cam_->OffsetX) )
{
return static_cast<size_t>(cam_->OffsetX.GetValue());
}
else
{
return 0;
}
}
template <typename CameraTraitT>
size_t PylonCameraImpl<CameraTraitT>::currentOffsetY()
{
if ( GenApi::IsAvailable(cam_->OffsetY) )
{
return static_cast<size_t>(cam_->OffsetY.GetValue());
}
else
{
return 0;
}
}
template <typename CameraTraitT>
sensor_msgs::RegionOfInterest PylonCameraImpl<CameraTraitT>::currentROI()
{
sensor_msgs::RegionOfInterest roi;
roi.width = cam_->Width.GetValue();
roi.height = cam_->Height.GetValue();
roi.x_offset = currentOffsetX();
roi.y_offset = currentOffsetY();
return roi;
}
template <typename CameraTraitT>
size_t PylonCameraImpl<CameraTraitT>::currentBinningX()
{
if ( GenApi::IsAvailable(cam_->BinningHorizontal) )
{
return static_cast<size_t>(cam_->BinningHorizontal.GetValue());
}
else
{
return 1;
}
}
template <typename CameraTraitT>
size_t PylonCameraImpl<CameraTraitT>::currentBinningY()
{
if ( GenApi::IsAvailable(cam_->BinningVertical) )
{
return static_cast<size_t>(cam_->BinningVertical.GetValue());
}
else
{
return 1;
}
}
template <typename CameraTraitT>
std::string PylonCameraImpl<CameraTraitT>::currentROSEncoding() const
{
std::string gen_api_encoding(cam_->PixelFormat.ToString().c_str());
std::string ros_encoding("");
if ( !encoding_conversions::genAPI2Ros(gen_api_encoding, ros_encoding) )
{
//std::stringstream ss;
//ss << "No ROS equivalent to GenApi encoding '" << gen_api_encoding << "' found! This is bad because this case should never occur!";
//throw std::runtime_error(ss.str());
ROS_ERROR_STREAM("No ROS equivalent to GenApi encoding");
cam_->StopGrabbing();
setImageEncoding(gen_api_encoding);
cam_->StartGrabbing();
//return "NO_ENCODING";
}
return ros_encoding;
}
template <typename CameraTraitT>
std::string PylonCameraImpl<CameraTraitT>::currentBaslerEncoding() const
{
return (cam_->PixelFormat.ToString().c_str());
}
template <typename CameraTraitT>
float PylonCameraImpl<CameraTraitT>::currentExposure()
{
return static_cast<float>(exposureTime().GetValue());
}
template <typename CameraTraitT>
float PylonCameraImpl<CameraTraitT>::currentGain()
{
float curr_gain = (static_cast<float>(gain().GetValue()) - static_cast<float>(gain().GetMin())) /
(static_cast<float>(gain().GetMax() - static_cast<float>(gain().GetMin())));
return curr_gain;
}
template <typename CameraTraitT>
GenApi::IFloat& PylonCameraImpl<CameraTraitT>::gamma()
{
if ( GenApi::IsAvailable(cam_->Gamma) )
{
return cam_->Gamma;
}
else
{
throw std::runtime_error("Error while accessing Gamma in PylonCameraImpl<CameraTraitT>");
}
}
template <typename CameraTraitT>
float PylonCameraImpl<CameraTraitT>::currentGamma()
{
return static_cast<float>(gamma().GetValue());
}
template <typename CameraTraitT>
float PylonCameraImpl<CameraTraitT>::currentAutoExposureTimeLowerLimit()
{
return static_cast<float>(autoExposureTimeLowerLimit().GetValue());
}
template <typename CameraTraitT>
float PylonCameraImpl<CameraTraitT>::currentAutoExposureTimeUpperLimit()
{
return static_cast<float>(autoExposureTimeUpperLimit().GetValue());
}
template <typename CameraTraitT>
float PylonCameraImpl<CameraTraitT>::currentAutoGainLowerLimit()
{
return static_cast<float>(autoGainLowerLimit().GetValue());
}
template <typename CameraTraitT>
float PylonCameraImpl<CameraTraitT>::currentAutoGainUpperLimit()
{
return static_cast<float>(autoGainUpperLimit().GetValue());
}
template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::isPylonAutoBrightnessFunctionRunning()
{
return cam_->ExposureAuto.GetValue() != ExposureAutoEnums::ExposureAuto_Off ||
cam_->GainAuto.GetValue() != GainAutoEnums::GainAuto_Off;
}
template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::isBrightnessSearchRunning()
{
return isBinaryExposureSearchRunning() || isPylonAutoBrightnessFunctionRunning();
}
template <typename CameraTraitT>
void PylonCameraImpl<CameraTraitT>::enableContinuousAutoExposure()
{
if ( GenApi::IsAvailable(cam_->ExposureAuto) )
{
cam_->ExposureAuto.SetValue(ExposureAutoEnums::ExposureAuto_Continuous);
}
else
{
ROS_ERROR_STREAM("Trying to enable ExposureAuto_Continuous mode, but "
<< "the camera has no Auto Exposure");
}
}
template <typename CameraTraitT>
void PylonCameraImpl<CameraTraitT>::enableContinuousAutoGain()
{
if ( GenApi::IsAvailable(cam_->GainAuto) )
{
cam_->GainAuto.SetValue(GainAutoEnums::GainAuto_Continuous);
}
else
{
ROS_ERROR_STREAM("Trying to enable GainAuto_Continuous mode, but "
<< "the camera has no Auto Gain");
}
}
template <typename CameraTraitT>
void PylonCameraImpl<CameraTraitT>::disableAllRunningAutoBrightessFunctions()
{
is_binary_exposure_search_running_ = false;
cam_->ExposureAuto.SetValue(ExposureAutoEnums::ExposureAuto_Off);
cam_->GainAuto.SetValue(GainAutoEnums::GainAuto_Off);
if ( binary_exp_search_ )
{
delete binary_exp_search_;
binary_exp_search_ = nullptr;
}
}
template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::setupSequencer(const std::vector<float>& exposure_times)
{
std::vector<float> exposure_times_set;
if ( setupSequencer(exposure_times, exposure_times_set) )
{
seq_exp_times_ = exposure_times_set;
std::stringstream ss;
ss << "Initialized sequencer with the following inverse exposure-times [1/s]: ";
for ( size_t i = 0; i < seq_exp_times_.size(); ++i )
{
ss << seq_exp_times_.at(i);
if ( i != seq_exp_times_.size() - 1 )
{
ss << ", ";
}
}
ROS_INFO_STREAM(ss.str());
return true;
}
else
{
return false;
}
}
template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::startGrabbing(const PylonCameraParameter& parameters)
{
try
{
if ( GenApi::IsAvailable(cam_->ShutterMode) )
{
setShutterMode(parameters.shutter_mode_);
}
available_image_encodings_ = detectAvailableImageEncodings(true);
if ( !(setImageEncoding(parameters.imageEncoding()).find("done") != std::string::npos) != 0 )
{
return false;
}
cam_->StartGrabbing();
user_output_selector_enums_ = detectAndCountNumUserOutputs();
device_user_id_ = cam_->DeviceUserID.GetValue();
img_rows_ = static_cast<size_t>(cam_->Height.GetValue());
img_cols_ = static_cast<size_t>(cam_->Width.GetValue());
img_size_byte_ = img_cols_ * img_rows_ * imagePixelDepth();
//grab_timeout_ = exposureTime().GetMax() * 1.05;
grab_timeout_ = 500; // grab timeout = 500 ms
// grab one image to be sure, that the communication is successful
Pylon::CGrabResultPtr grab_result;
grab(grab_result);
if ( grab_result.IsValid() )
{
is_ready_ = true;
}
else
{
ROS_ERROR("PylonCamera not ready because the result of the initial grab is invalid");
}
}
catch ( const GenICam::GenericException &e )
{
ROS_ERROR_STREAM("startGrabbing: " << e.GetDescription());
return false;
}
return true;
}
// Grab a picture as std::vector of 8bits objects
template <typename CameraTrait>
bool PylonCameraImpl<CameraTrait>::grab(std::vector<uint8_t>& image)
{
Pylon::CGrabResultPtr ptr_grab_result;
if ( !grab(ptr_grab_result) )
{
ROS_ERROR("Error: Grab was not successful");
return false;
}
const uint8_t *pImageBuffer = reinterpret_cast<uint8_t*>(ptr_grab_result->GetBuffer());
// ------------------------------------------------------------------------
// Bit shifting
// ------------------------------------------------------------------------
// In case of 12 bits we need to shift the image bits 4 positions to the left
std::string ros_enc = currentROSEncoding();
uint16_t * shift_array = new uint16_t[img_size_byte_ / 2]; // Dynamically allocated to avoid heap size error
std::string gen_api_encoding(cam_->PixelFormat.ToString().c_str());
if (encoding_conversions::is_12_bit_ros_enc(ros_enc) && (gen_api_encoding == "BayerRG12" || gen_api_encoding == "BayerBG12" || gen_api_encoding == "BayerGB12" || gen_api_encoding == "BayerGR12" || gen_api_encoding == "Mono12") ){
const uint16_t *convert_bits = reinterpret_cast<uint16_t*>(ptr_grab_result->GetBuffer());
for (int i = 0; i < img_size_byte_ / 2; i++){
shift_array[i] = convert_bits[i] << 4;
}
image.assign((uint8_t *) shift_array, (uint8_t *) shift_array + img_size_byte_);
} else {
image.assign(pImageBuffer, pImageBuffer + img_size_byte_);
}
delete[] shift_array;
if ( !is_ready_ )
is_ready_ = true;
return true;
}
// Grab a picture as pointer to 8bit array
template <typename CameraTrait>
bool PylonCameraImpl<CameraTrait>::grab(uint8_t* image)
{
// If camera is not grabbing, don't grab
if (!cam_->IsGrabbing()){
return false;
}
Pylon::CGrabResultPtr ptr_grab_result;
if ( !grab(ptr_grab_result) )
{
ROS_ERROR("Error: Grab was not successful");
return false;
}
// ------------------------------------------------------------------------
// Bit shifting
// ------------------------------------------------------------------------
// In case of 12 bits we need to shift the image bits 4 positions to the left
std::string ros_enc = currentROSEncoding();
uint16_t shift_array[img_size_byte_ / 2];
if (encoding_conversions::is_12_bit_ros_enc(ros_enc)){
const uint16_t *convert_bits = reinterpret_cast<uint16_t*>(ptr_grab_result->GetBuffer());
for (int i = 0; i < img_size_byte_ / 2; i++){
shift_array[i] = convert_bits[i] << 4;
}
memcpy(image, (uint8_t *) shift_array, img_size_byte_);
} else {
memcpy(image, ptr_grab_result->GetBuffer(), img_size_byte_);
}
return true;
}
// Lowest level grab function called by the other grab functions
template <typename CameraTrait>
bool PylonCameraImpl<CameraTrait>::grab(Pylon::CGrabResultPtr& grab_result)
{
// If camera is not grabbing, don't grab
if (!cam_->IsGrabbing()){
return false;
}
try
{
int timeout = 5000; // ms
// WaitForFrameTriggerReady to prevent trigger signal to get lost
// this could happen, if 2xExecuteSoftwareTrigger() is only followed by 1xgrabResult()
// -> 2nd trigger might get lost
if ((cam_->TriggerMode.GetValue() == TriggerModeEnums::TriggerMode_On))
{
if ( cam_->WaitForFrameTriggerReady(timeout, Pylon::TimeoutHandling_ThrowException) )
{
cam_->ExecuteSoftwareTrigger();
}
else
{
ROS_ERROR("Error WaitForFrameTriggerReady() timed out, impossible to ExecuteSoftwareTrigger()");
return false;
}
}
cam_->RetrieveResult(grab_timeout_, grab_result, Pylon::TimeoutHandling_ThrowException);
}
catch ( const GenICam::GenericException &e )
{
if ( cam_->IsCameraDeviceRemoved() )
{
ROS_ERROR("Lost connection to the camera . . .");
}
else
{
if ((! cam_->TriggerSource.GetValue() == TriggerSourceEnums::TriggerSource_Software) && (cam_->TriggerMode.GetValue() == TriggerModeEnums::TriggerMode_On))
{
ROS_ERROR_STREAM("Waiting for Trigger signal");
}
else
{
ROS_ERROR_STREAM("An image grabbing exception in pylon camera occurred: "
<< e.GetDescription());
}
}
return false;
}
catch (...)
{
ROS_ERROR("An unspecified image grabbing exception in pylon camera occurred");
return false;
}
if ( !grab_result->GrabSucceeded() )
{
ROS_ERROR_STREAM("Error: " << grab_result->GetErrorCode() << " "
<< grab_result->GetErrorDescription());
return false;
}
return true;
}
template <typename CameraTraitT>
std::vector<std::string> PylonCameraImpl<CameraTraitT>::detectAvailableImageEncodings(const bool& show_message)
{
std::vector<std::string> available_encodings;
GenApi::INodeMap& node_map = cam_->GetNodeMap();
GenApi::CEnumerationPtr img_encoding_enumeration_ptr(
node_map.GetNode("PixelFormat"));
GenApi::NodeList_t feature_list;
img_encoding_enumeration_ptr->GetEntries(feature_list);
std::stringstream ss;
ss << "Cam supports the following [GenAPI|ROS] image encodings: ";
for (GenApi::NodeList_t::iterator it = feature_list.begin();
it != feature_list.end();
++it)
{
if ( GenApi::IsAvailable(*it) )
{
GenApi::CEnumEntryPtr enum_entry(*it);
std::string encoding_gen_api = enum_entry->GetSymbolic().c_str();
std::string encoding_ros("NO_ROS_EQUIVALENT");
encoding_conversions::genAPI2Ros(encoding_gen_api, encoding_ros);
ss << "['" << encoding_gen_api << "'|'" << encoding_ros << "'] ";
available_encodings.push_back(encoding_gen_api);
}
}
if (show_message)
ROS_INFO_STREAM(ss.str().c_str());
return available_encodings;
}
template <typename CameraTraitT>
std::string PylonCameraImpl<CameraTraitT>::setImageEncoding(const std::string& ros_encoding) const
{
bool is_16bits_available = false;
bool is_encoding_available = false;
std::string gen_api_encoding;
// An additional check to select the correct basler encoding, as ROS 16-bits encoding will cover both Basler 12-bits and 16-bits encoding
if (ros_encoding == "bayer_rggb16" || ros_encoding == "bayer_bggr16" || ros_encoding == "bayer_gbrg16" || ros_encoding == "bayer_grbg16")
{
for ( const std::string& enc : available_image_encodings_ )
{
if ( enc == "BayerRG16" || enc == "BayerBG16" || enc == "BayerGB16" || enc == "BayerGR16" || enc == "Mono16" )
{
is_16bits_available = true;
break;
}
}
}
bool conversion_found = encoding_conversions::ros2GenAPI(ros_encoding, gen_api_encoding, is_16bits_available);
if (ros_encoding != "")
{
for ( const std::string& enc : available_image_encodings_ )
{
if ((gen_api_encoding == enc) && conversion_found)
{
is_encoding_available = true;
break;
}
}
if (! is_encoding_available)
return "Error: unsporrted/unknown image format";
}
if ( !conversion_found )
{
if ( ros_encoding.empty() )
{
ROS_WARN_STREAM("No image encoding provided. Will use 'mono8' or "
<< "'rgb8' as fallback!");
}
else
{
ROS_ERROR_STREAM("Can't convert ROS encoding '" << ros_encoding
<< "' to a corresponding GenAPI encoding! Will use 'mono8' or "
<< "'rgb8' as fallback!");
}
bool fallback_found = false;
for ( const std::string& enc : available_image_encodings_ )
{
if ( enc == "Mono8" || enc == "RGB8" )
{
fallback_found = true;
gen_api_encoding = enc;
break;
}
}
if ( !fallback_found )
{
ROS_ERROR_STREAM("Couldn't find a fallback solution!");
return "Error: Couldn't find a fallback solution!";
}
}
bool supports_desired_encoding = false;
for ( const std::string& enc : available_image_encodings_ )
{
supports_desired_encoding = (gen_api_encoding == enc);
if ( supports_desired_encoding )
{
break;
}
}
if ( !supports_desired_encoding )
{
ROS_WARN_STREAM("Camera does not support the desired image pixel "
<< "encoding '" << ros_encoding << "'!");
return "Error : Camera does not support the desired image pixel";
}
try
{
if ( GenApi::IsAvailable(cam_->PixelFormat) )
{
GenApi::INodeMap& node_map = cam_->GetNodeMap();
GenApi::CEnumerationPtr(node_map.GetNode("PixelFormat"))->FromString(gen_api_encoding.c_str());
return "done";
}
else
{
ROS_WARN_STREAM("Camera does not support variable image pixel "
<< "encoding!");
return "Error : Camera does not support variable image pixel";
}
}
catch ( const GenICam::GenericException &e )
{
ROS_ERROR_STREAM("An exception while setting target image encoding to '"
<< ros_encoding << "' occurred: " << e.GetDescription());
return e.GetDescription();
}
}
template <typename CameraTraitT>
int PylonCameraImpl<CameraTraitT>::imagePixelDepth() const
{
int pixel_depth(0);
try
{
// pylon PixelSize already contains the number of channels
// the size is given in bit, wheras ROS provides it in byte
pixel_depth = cam_->PixelSize.GetIntValue() / 8;
}
catch ( const GenICam::GenericException &e )
{
ROS_ERROR_STREAM("An exception while reading image pixel size occurred: "
<< e.GetDescription());
}
return pixel_depth;
}
template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::setROI(const sensor_msgs::RegionOfInterest target_roi,
sensor_msgs::RegionOfInterest& reached_roi)
{
size_t width_to_set = target_roi.width;
size_t height_to_set = target_roi.height;
size_t offset_x_to_set = target_roi.x_offset;
size_t offset_y_to_set = target_roi.y_offset;
try
{
if ( GenApi::IsAvailable(cam_->Width) && GenApi::IsAvailable(cam_->Height) && GenApi::IsAvailable(cam_->OffsetX) && GenApi::IsAvailable(cam_->OffsetY))
{
cam_->StopGrabbing();
int64_t max_image_width = cam_->WidthMax.GetValue();
int64_t min_image_width = cam_->Width.GetMin();
int64_t max_image_height = cam_->HeightMax.GetValue();
int64_t min_image_height = cam_->Height.GetMin();
int64_t width_inc = cam_->Width.GetInc();
int64_t height_inc = cam_->Height.GetInc();
// reset roi to avoid exceptions while setting Width and Height values
cam_->OffsetX.SetValue(0);
cam_->OffsetY.SetValue(0);
cam_->Width.SetValue(max_image_width);
cam_->Height.SetValue(max_image_height);
sensor_msgs::RegionOfInterest current_roi = currentROI();
// Force minimum increment of 2 as some cameras wrongly declare that
// they have an increment of 1 while it is 2
if (height_inc == 1)
height_inc = 2;
if (width_inc == 1)
width_inc = 2;
if (width_to_set > max_image_width)
{
ROS_WARN_STREAM("Desired width("
<< width_to_set << ") unreachable! Setting to upper "
<< "limit: " << max_image_width);
width_to_set = max_image_width;
}
else if (width_to_set < min_image_width)
{
ROS_WARN_STREAM("Desired width("
<< width_to_set << ") unreachable! Setting to lower "
<< "limit: " << min_image_width);
width_to_set = min_image_width;
}
if (height_to_set > max_image_height)
{
ROS_WARN_STREAM("Desired height("
<<height_to_set << ") unreachable! Setting to upper "
<< "limit: " << max_image_height);
height_to_set = max_image_height;
}
else if (height_to_set < min_image_height)
{
ROS_WARN_STREAM("Desired height("
<< height_to_set << ") unreachable! Setting to lower "
<< "limit: " << min_image_height);
height_to_set = min_image_height;
}
if (offset_x_to_set % width_inc != 0)
{
int64_t adapted_offset_x = offset_x_to_set + (width_inc - offset_x_to_set % width_inc);
ROS_WARN_STREAM("Desired x offset ("
<< offset_x_to_set << ") not an multiple of width increment("
<< width_inc <<")! Setting to next possible value higher multiple: ("
<< adapted_offset_x <<")");
offset_x_to_set = adapted_offset_x;
}
if (width_to_set + offset_x_to_set > max_image_width)
{
int64_t adapted_offset_x = max_image_width - width_to_set;
adapted_offset_x -= adapted_offset_x % width_inc;
ROS_WARN_STREAM("Desired x offset("
<< offset_x_to_set << ") impossible for desired width("
<< width_to_set << ")! Setting to next possible value "
<< adapted_offset_x);
offset_x_to_set = adapted_offset_x;
}
if (offset_y_to_set % height_inc != 0)
{
int64_t adapted_offset_y = offset_y_to_set + (height_inc - offset_y_to_set % height_inc);
ROS_WARN_STREAM("Desired y offset ("
<< offset_y_to_set << ") not an multiple ofheight increment("
<< height_inc <<")! Setting to next possible value higher multiple: ("
<< adapted_offset_y <<")");
offset_y_to_set = adapted_offset_y;
}
if (height_to_set + offset_y_to_set > max_image_height)
{
int64_t adapted_offset_y = max_image_height - height_to_set;
adapted_offset_y -= adapted_offset_y % height_inc;
ROS_WARN_STREAM("Desired y offset("
<< offset_y_to_set << ") impossible for desired height("
<< height_to_set << ")! Setting to next possible value "
<< adapted_offset_y);
offset_y_to_set = adapted_offset_y;
}
cam_->Width.SetValue(width_to_set);
cam_->Height.SetValue(height_to_set);
cam_->OffsetX.SetValue(offset_x_to_set);
cam_->OffsetY.SetValue(offset_y_to_set);
reached_roi = currentROI();
img_cols_ = static_cast<size_t>(cam_->Width.GetValue());
img_rows_ = static_cast<size_t>(cam_->Height.GetValue());
img_size_byte_ = img_cols_ * img_rows_ * imagePixelDepth();
// For ACE cameras we need to completely stop grabbing and then the
// user needs to call start grabbing, if not the driver crashes.
// in pylon_camera_node.cpp values are updated after this call, so that
// we cannot start now grabbing until those values are updated
}
else
{
ROS_WARN_STREAM("Camera does not support area of interest. Will keep the "
<< "current settings");
reached_roi = currentROI();
}
}
catch ( const GenICam::GenericException &e )
{
ROS_ERROR_STREAM("An exception while setting target area of interest "
<< "(width, height, x_offset, y_offset) to: (" << width_to_set << ", "
<< height_to_set << ", " << offset_x_to_set << ", " << offset_y_to_set <<
") occurred: "
<< e.GetDescription());
return false;
}
return true;
}
template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::setBinningX(const size_t& target_binning_x,
size_t& reached_binning_x)
{
try
{
if ( GenApi::IsAvailable(cam_->BinningHorizontal) )
{
cam_->StopGrabbing();
size_t binning_x_to_set = target_binning_x;
if ( binning_x_to_set < cam_->BinningHorizontal.GetMin() )
{
ROS_WARN_STREAM("Desired horizontal binning_x factor("
<< binning_x_to_set << ") unreachable! Setting to lower "
<< "limit: " << cam_->BinningHorizontal.GetMin());
binning_x_to_set = cam_->BinningHorizontal.GetMin();
}
else if ( binning_x_to_set > cam_->BinningHorizontal.GetMax() )
{
ROS_WARN_STREAM("Desired horizontal binning_x factor("
<< binning_x_to_set << ") unreachable! Setting to upper "
<< "limit: " << cam_->BinningHorizontal.GetMax());
binning_x_to_set = cam_->BinningHorizontal.GetMax();
}
cam_->BinningHorizontal.SetValue(binning_x_to_set);
reached_binning_x = currentBinningX();
cam_->StartGrabbing();
img_cols_ = static_cast<size_t>(cam_->Width.GetValue());
img_size_byte_ = img_cols_ * img_rows_ * imagePixelDepth();
}
else
{
ROS_WARN_STREAM("Camera does not support binning. Will keep the "
<< "current settings");
reached_binning_x = currentBinningX();
}
}
catch ( const GenICam::GenericException &e )
{
ROS_ERROR_STREAM("An exception while setting target horizontal "
<< "binning_x factor to " << target_binning_x << " occurred: "
<< e.GetDescription());
return false;
}
return true;
}
template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::setBinningY(const size_t& target_binning_y,
size_t& reached_binning_y)
{
try
{
if ( GenApi::IsAvailable(cam_->BinningVertical) )
{
cam_->StopGrabbing();
size_t binning_y_to_set = target_binning_y;
if ( binning_y_to_set < cam_->BinningVertical.GetMin() )
{
ROS_WARN_STREAM("Desired vertical binning_y factor("
<< binning_y_to_set << ") unreachable! Setting to lower "
<< "limit: " << cam_->BinningVertical.GetMin());
binning_y_to_set = cam_->BinningVertical.GetMin();
}
else if ( binning_y_to_set > cam_->BinningVertical.GetMax() )
{
ROS_WARN_STREAM("Desired vertical binning_y factor("
<< binning_y_to_set << ") unreachable! Setting to upper "
<< "limit: " << cam_->BinningVertical.GetMax());
binning_y_to_set = cam_->BinningVertical.GetMax();
}
cam_->BinningVertical.SetValue(binning_y_to_set);
reached_binning_y = currentBinningY();
cam_->StartGrabbing();
img_rows_ = static_cast<size_t>(cam_->Height.GetValue());
img_size_byte_ = img_cols_ * img_rows_ * imagePixelDepth();
}
else
{
ROS_WARN_STREAM("Camera does not support binning. Will keep the "
<< "current settings");
reached_binning_y = currentBinningY();
}
}
catch ( const GenICam::GenericException &e )
{
ROS_ERROR_STREAM("An exception while setting target vertical "
<< "binning_y factor to " << target_binning_y << " occurred: "
<< e.GetDescription());
return false;
}
return true;
}
template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::setExposure(const float& target_exposure,
float& reached_exposure)
{
try
{
cam_->ExposureAuto.SetValue(ExposureAutoEnums::ExposureAuto_Off);
float exposure_to_set = target_exposure;
if ( exposure_to_set < exposureTime().GetMin() )
{
ROS_WARN_STREAM("Desired exposure (" << exposure_to_set << ") "
<< "time unreachable! Setting to lower limit: "
<< exposureTime().GetMin());
exposure_to_set = exposureTime().GetMin();
}
else if ( exposure_to_set > exposureTime().GetMax() )
{
ROS_WARN_STREAM("Desired exposure (" << exposure_to_set << ") "
<< "time unreachable! Setting to upper limit: "
<< exposureTime().GetMax());
exposure_to_set = exposureTime().GetMax();
}
exposureTime().SetValue(exposure_to_set);
reached_exposure = currentExposure();
if ( std::fabs(reached_exposure - exposure_to_set) > exposureStep() )
{
// no success if the delta between target and reached exposure
// is greater then the exposure step in ms
return false;
}
}
catch ( const GenICam::GenericException &e )
{
ROS_ERROR_STREAM("An exception while setting target exposure to "
<< target_exposure << " occurred:"
<< e.GetDescription());
return false;
}
return true;
}
template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::setAutoflash(
const std::map<int, bool> flash_on_lines)
{
ROS_ERROR_STREAM("Not implemented for this camera type");
return false;
}
template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::setGain(const float& target_gain,
float& reached_gain)
{
try
{
cam_->GainAuto.SetValue(GainAutoEnums::GainAuto_Off);
float truncated_gain = target_gain;
if ( truncated_gain < 0.0 )
{
ROS_WARN_STREAM("Desired gain (" << target_gain << ") in "
<< "percent out of range [0.0 - 1.0]! Setting to lower "
<< "limit: 0.0");
truncated_gain = 0.0;
}
else if ( truncated_gain > 1.0 )
{
ROS_WARN_STREAM("Desired gain (" << target_gain << ") in "
<< "percent out of range [0.0 - 1.0]! Setting to upper "
<< "limit: 1.0");
truncated_gain = 1.0;
}
float gain_to_set = gain().GetMin() +
truncated_gain * (gain().GetMax() - gain().GetMin());
gain().SetValue(gain_to_set);
reached_gain = currentGain();
}
catch ( const GenICam::GenericException &e )
{
ROS_ERROR_STREAM("An exception while setting target gain to "
<< target_gain << " occurred: " << e.GetDescription());
return false;
}
return true;
}
template <typename CameraTraitT>
bool PylonCameraImpl<CameraTraitT>::setBrightness(const int& target_brightness,
const float& current_brightness,
const bool& exposure_auto,
const bool& gain_auto)
{
try
{
// if the target brightness is greater 255, limit it to 255
// the brightness_to_set is a float value, regardless of the current
// pixel data output format, i.e., 0.0 -> black, 1.0 -> white.
typename CameraTraitT::AutoTargetBrightnessValueType brightness_to_set =
CameraTraitT::convertBrightness(std::min(255, target_brightness));
#if DEBUG
std::cout << "br = " << current_brightness << ", gain = "
<< currentGain() << ", exp = "
<< currentExposure()