-
Notifications
You must be signed in to change notification settings - Fork 108
/
pylon_camera_node.cpp
1497 lines (1363 loc) · 55.3 KB
/
pylon_camera_node.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
/******************************************************************************
* Software License Agreement (BSD License)
*
* Copyright (C) 2016, Magazino GmbH. 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 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.
*****************************************************************************/
#include <pylon_camera/pylon_camera_node.h>
#include <GenApi/GenApi.h>
#include <algorithm>
#include <cmath>
#include <vector>
#include "boost/multi_array.hpp"
namespace pylon_camera
{
using sensor_msgs::CameraInfo;
using sensor_msgs::CameraInfoPtr;
PylonCameraNode::PylonCameraNode()
: nh_("~"),
pylon_camera_parameter_set_(),
set_binning_srv_(nh_.advertiseService("set_binning",
&PylonCameraNode::setBinningCallback,
this)),
set_exposure_srv_(nh_.advertiseService("set_exposure",
&PylonCameraNode::setExposureCallback,
this)),
set_gain_srv_(nh_.advertiseService("set_gain",
&PylonCameraNode::setGainCallback,
this)),
set_gamma_srv_(nh_.advertiseService("set_gamma",
&PylonCameraNode::setGammaCallback,
this)),
set_brightness_srv_(nh_.advertiseService("set_brightness",
&PylonCameraNode::setBrightnessCallback,
this)),
set_sleeping_srv_(nh_.advertiseService("set_sleeping",
&PylonCameraNode::setSleepingCallback,
this)),
set_user_output_srvs_(),
pylon_camera_(nullptr),
it_(new image_transport::ImageTransport(nh_)),
img_raw_pub_(it_->advertiseCamera("image_raw", 1)),
img_rect_pub_(nullptr),
grab_imgs_raw_as_(
nh_,
"grab_images_raw",
boost::bind(&PylonCameraNode::grabImagesRawActionExecuteCB,
this,
_1),
false),
grab_imgs_rect_as_(nullptr),
pinhole_model_(nullptr),
cv_bridge_img_rect_(nullptr),
camera_info_manager_(new camera_info_manager::CameraInfoManager(nh_)),
sampling_indices_(),
brightness_exp_lut_(),
is_sleeping_(false)
{
init();
}
void PylonCameraNode::init()
{
// reading all necessary parameter to open the desired camera from the
// ros-parameter-server. In case that invalid parameter values can be
// detected, the interface will reset them to the default values.
// These parameters furthermore contain the intrinsic calibration matrices,
// in case they are provided
pylon_camera_parameter_set_.readFromRosParameterServer(nh_);
// creating the target PylonCamera-Object with the specified
// device_user_id, registering the Software-Trigger-Mode, starting the
// communication with the device and enabling the desired startup-settings
if ( !initAndRegister() )
{
ros::shutdown();
return;
}
// starting the grabbing procedure with the desired image-settings
if ( !startGrabbing() )
{
ros::shutdown();
return;
}
}
bool PylonCameraNode::initAndRegister()
{
pylon_camera_ = PylonCamera::create(
pylon_camera_parameter_set_.deviceUserID());
if ( pylon_camera_ == nullptr )
{
// wait and retry until a camera is present
ros::Time end = ros::Time::now() + ros::Duration(15.0);
ros::Rate r(0.5);
while ( ros::ok() && pylon_camera_ == nullptr )
{
pylon_camera_ = PylonCamera::create(
pylon_camera_parameter_set_.deviceUserID());
if ( ros::Time::now() > end )
{
ROS_WARN_STREAM("No camera present. Keep waiting ...");
end = ros::Time::now() + ros::Duration(15.0);
}
r.sleep();
ros::spinOnce();
}
}
if ( !ros::ok() )
{
return false;
}
if ( !pylon_camera_->registerCameraConfiguration() )
{
ROS_ERROR_STREAM("Error while registering the camera configuration to "
<< "software-trigger mode!");
return false;
}
if ( !pylon_camera_->openCamera() )
{
ROS_ERROR("Error while trying to open the desired camera!");
return false;
}
if ( !pylon_camera_->applyCamSpecificStartupSettings(pylon_camera_parameter_set_) )
{
ROS_ERROR_STREAM("Error while applying the cam specific startup settings "
<< "(e.g. mtu size for GigE, ...) to the camera!");
return false;
}
return true;
}
bool PylonCameraNode::startGrabbing()
{
if ( !pylon_camera_->startGrabbing(pylon_camera_parameter_set_) )
{
ROS_ERROR("Error while start grabbing");
return false;
}
set_user_output_srvs_.resize(pylon_camera_->numUserOutputs());
for ( int i = 0; i < set_user_output_srvs_.size(); ++i )
{
std::string srv_name = "set_user_output_" + std::to_string(i);
set_user_output_srvs_.at(i) =
nh_.advertiseService< camera_control_msgs::SetBool::Request,
camera_control_msgs::SetBool::Response >(
srv_name,
boost::bind(&PylonCameraNode::setUserOutputCB,
this,
i,
_1,
_2));
}
img_raw_msg_.header.frame_id = pylon_camera_parameter_set_.cameraFrame();
// Encoding of pixels -- channel meaning, ordering, size
// taken from the list of strings in include/sensor_msgs/image_encodings.h
img_raw_msg_.encoding = pylon_camera_->currentROSEncoding();
img_raw_msg_.height = pylon_camera_->imageRows();
img_raw_msg_.width = pylon_camera_->imageCols();
// step = full row length in bytes, img_size = (step * rows), imagePixelDepth
// already contains the number of channels
img_raw_msg_.step = img_raw_msg_.width * pylon_camera_->imagePixelDepth();
if ( !camera_info_manager_->setCameraName(pylon_camera_->deviceUserID()) )
{
// valid name contains only alphanumerc signs and '_'
ROS_WARN_STREAM("[" << pylon_camera_->deviceUserID()
<< "] name not valid for camera_info_manger");
}
setupSamplingIndices(sampling_indices_,
pylon_camera_->imageRows(),
pylon_camera_->imageCols(),
pylon_camera_parameter_set_.downsampling_factor_exp_search_);
grab_imgs_raw_as_.start();
// Initial setting of the CameraInfo-msg, assuming no calibration given
CameraInfo initial_cam_info;
setupInitialCameraInfo(initial_cam_info);
camera_info_manager_->setCameraInfo(initial_cam_info);
if ( pylon_camera_parameter_set_.cameraInfoURL().empty() ||
!camera_info_manager_->validateURL(pylon_camera_parameter_set_.cameraInfoURL()) )
{
ROS_INFO_STREAM("CameraInfoURL needed for rectification! ROS-Param: "
<< "'" << nh_.getNamespace() << "/camera_info_url' = '"
<< pylon_camera_parameter_set_.cameraInfoURL() << "' is invalid!");
ROS_DEBUG_STREAM("CameraInfoURL should have following style: "
<< "'file:///full/path/to/local/file.yaml' or "
<< "'file://${ROS_HOME}/camera_info/${NAME}.yaml'");
ROS_WARN("Will only provide distorted /image_raw images!");
}
else
{
// override initial camera info if the url is valid
if ( camera_info_manager_->loadCameraInfo(
pylon_camera_parameter_set_.cameraInfoURL()) )
{
setupRectification();
// set the correct tf frame_id
CameraInfoPtr cam_info(new CameraInfo(
camera_info_manager_->getCameraInfo()));
cam_info->header.frame_id = img_raw_msg_.header.frame_id;
camera_info_manager_->setCameraInfo(*cam_info);
}
else
{
ROS_WARN("Will only provide distorted /image_raw images!");
}
}
if ( pylon_camera_parameter_set_.binning_x_given_ )
{
size_t reached_binning_x;
setBinningX(pylon_camera_parameter_set_.binning_x_, reached_binning_x);
ROS_INFO_STREAM("Setting horizontal binning_x to "
<< pylon_camera_parameter_set_.binning_x_);
ROS_WARN_STREAM("The image width of the camera_info-msg will "
<< "be adapted, so that the binning_x value in this msg remains 1");
}
if ( pylon_camera_parameter_set_.binning_y_given_ )
{
size_t reached_binning_y;
setBinningY(pylon_camera_parameter_set_.binning_y_, reached_binning_y);
ROS_INFO_STREAM("Setting vertical binning_y to "
<< pylon_camera_parameter_set_.binning_y_);
ROS_WARN_STREAM("The image height of the camera_info-msg will "
<< "be adapted, so that the binning_y value in this msg remains 1");
}
if ( pylon_camera_parameter_set_.exposure_given_ )
{
float reached_exposure;
setExposure(pylon_camera_parameter_set_.exposure_, reached_exposure);
ROS_INFO_STREAM("Setting exposure to "
<< pylon_camera_parameter_set_.exposure_ << ", reached: "
<< reached_exposure);
}
if ( pylon_camera_parameter_set_.gain_given_ )
{
float reached_gain;
setGain(pylon_camera_parameter_set_.gain_, reached_gain);
ROS_INFO_STREAM("Setting gain to: "
<< pylon_camera_parameter_set_.gain_ << ", reached: "
<< reached_gain);
}
if ( pylon_camera_parameter_set_.gamma_given_ )
{
float reached_gamma;
setGamma(pylon_camera_parameter_set_.gamma_, reached_gamma);
ROS_INFO_STREAM("Setting gamma to " << pylon_camera_parameter_set_.gamma_
<< ", reached: " << reached_gamma);
}
if ( pylon_camera_parameter_set_.brightness_given_ )
{
int reached_brightness;
setBrightness(pylon_camera_parameter_set_.brightness_,
reached_brightness,
pylon_camera_parameter_set_.exposure_auto_,
pylon_camera_parameter_set_.gain_auto_);
ROS_INFO_STREAM("Setting brightness to: "
<< pylon_camera_parameter_set_.brightness_ << ", reached: "
<< reached_brightness);
if ( pylon_camera_parameter_set_.brightness_continuous_ )
{
if ( pylon_camera_parameter_set_.exposure_auto_ )
{
pylon_camera_->enableContinuousAutoExposure();
}
if ( pylon_camera_parameter_set_.gain_auto_ )
{
pylon_camera_->enableContinuousAutoGain();
}
}
else
{
pylon_camera_->disableAllRunningAutoBrightessFunctions();
}
}
ROS_INFO_STREAM("Startup settings: "
<< "encoding = '" << pylon_camera_->currentROSEncoding() << "', "
<< "binning = [" << pylon_camera_->currentBinningX() << ", "
<< pylon_camera_->currentBinningY() << "], "
<< "exposure = " << pylon_camera_->currentExposure() << ", "
<< "gain = " << pylon_camera_->currentGain() << ", "
<< "gamma = " << pylon_camera_->currentGamma() << ", "
<< "shutter mode = "
<< pylon_camera_parameter_set_.shutterModeString());
// Framerate Settings
if ( pylon_camera_->maxPossibleFramerate() < pylon_camera_parameter_set_.frameRate() )
{
ROS_INFO("Desired framerate %.2f is higher than max possible. Will limit framerate to: %.2f Hz",
pylon_camera_parameter_set_.frameRate(),
pylon_camera_->maxPossibleFramerate());
pylon_camera_parameter_set_.setFrameRate(
nh_,
pylon_camera_->maxPossibleFramerate());
}
else if ( pylon_camera_parameter_set_.frameRate() == -1 )
{
pylon_camera_parameter_set_.setFrameRate(nh_,
pylon_camera_->maxPossibleFramerate());
ROS_INFO("Max possible framerate is %.2f Hz",
pylon_camera_->maxPossibleFramerate());
}
return true;
}
void PylonCameraNode::setupRectification()
{
if ( !img_rect_pub_ )
{
img_rect_pub_ = new ros::Publisher(
nh_.advertise<sensor_msgs::Image>("image_rect", 1));
}
if ( !grab_imgs_rect_as_ )
{
grab_imgs_rect_as_ =
new GrabImagesAS(nh_,
"grab_images_rect",
boost::bind(
&PylonCameraNode::grabImagesRectActionExecuteCB,
this,
_1),
false);
grab_imgs_rect_as_->start();
}
if ( !pinhole_model_ )
{
pinhole_model_ = new image_geometry::PinholeCameraModel();
}
pinhole_model_->fromCameraInfo(camera_info_manager_->getCameraInfo());
if ( !cv_bridge_img_rect_ )
{
cv_bridge_img_rect_ = new cv_bridge::CvImage();
}
cv_bridge_img_rect_->header = img_raw_msg_.header;
cv_bridge_img_rect_->encoding = img_raw_msg_.encoding;
}
void PylonCameraNode::spin()
{
if ( camera_info_manager_->isCalibrated() )
{
ROS_INFO_ONCE("Camera is calibrated");
}
else
{
ROS_INFO_ONCE("Camera not calibrated");
}
if ( pylon_camera_->isCamRemoved() )
{
ROS_ERROR("Pylon camera has been removed, trying to reset");
delete pylon_camera_;
pylon_camera_ = nullptr;
for ( ros::ServiceServer& user_output_srv : set_user_output_srvs_ )
{
user_output_srv.shutdown();
}
set_user_output_srvs_.clear();
ros::Duration(0.5).sleep(); // sleep for half a second
init();
return;
}
// images were published if subscribers are available or if someone calls
// the GrabImages Action
if ( !isSleeping() && ( img_raw_pub_.getNumSubscribers() > 0 ||
getNumSubscribersRect() ) )
{
if ( !grabImage() )
{
return;
}
if ( img_raw_pub_.getNumSubscribers() > 0 )
{
// get actual cam_info-object in every frame, because it might have
// changed due to a 'set_camera_info'-service call
sensor_msgs::CameraInfoPtr cam_info(
new sensor_msgs::CameraInfo(
camera_info_manager_->getCameraInfo()));
cam_info->header.stamp = img_raw_msg_.header.stamp;
// Publish via image_transport
img_raw_pub_.publish(img_raw_msg_, *cam_info);
}
if ( getNumSubscribersRect() > 0 && camera_info_manager_->isCalibrated() )
{
cv_bridge_img_rect_->header.stamp = img_raw_msg_.header.stamp;
assert(pinhole_model_->initialized());
cv_bridge::CvImagePtr cv_img_raw = cv_bridge::toCvCopy(
img_raw_msg_,
img_raw_msg_.encoding);
pinhole_model_->fromCameraInfo(camera_info_manager_->getCameraInfo());
pinhole_model_->rectifyImage(cv_img_raw->image, cv_bridge_img_rect_->image);
img_rect_pub_->publish(*cv_bridge_img_rect_);
}
}
}
bool PylonCameraNode::grabImage()
{
boost::lock_guard<boost::recursive_mutex> lock(grab_mutex_);
if ( !pylon_camera_->grab(img_raw_msg_.data) )
{
ROS_WARN("Pylon camera returned invalid image! Skipping");
return false;
}
img_raw_msg_.header.stamp = ros::Time::now();
return true;
}
void PylonCameraNode::grabImagesRawActionExecuteCB(
const camera_control_msgs::GrabImagesGoal::ConstPtr& goal)
{
camera_control_msgs::GrabImagesResult result;
result = grabImagesRaw(goal, &grab_imgs_raw_as_);
grab_imgs_raw_as_.setSucceeded(result);
}
void PylonCameraNode::grabImagesRectActionExecuteCB(
const camera_control_msgs::GrabImagesGoal::ConstPtr& goal)
{
camera_control_msgs::GrabImagesResult result;
if ( !camera_info_manager_->isCalibrated() )
{
result.success = false;
grab_imgs_rect_as_->setSucceeded(result);
return;
}
else
{
result = grabImagesRaw(goal, std::ref(grab_imgs_rect_as_));
if ( !result.success )
{
grab_imgs_rect_as_->setSucceeded(result);
return;
}
for ( std::size_t i = 0; i < result.images.size(); ++i)
{
cv_bridge::CvImagePtr cv_img_raw = cv_bridge::toCvCopy(
result.images[i],
result.images[i].encoding);
pinhole_model_->fromCameraInfo(camera_info_manager_->getCameraInfo());
cv_bridge::CvImage cv_bridge_img_rect;
cv_bridge_img_rect.header = result.images[i].header;
cv_bridge_img_rect.encoding = result.images[i].encoding;
pinhole_model_->rectifyImage(cv_img_raw->image, cv_bridge_img_rect.image);
cv_bridge_img_rect.toImageMsg(result.images[i]);
}
grab_imgs_rect_as_->setSucceeded(result);
}
}
camera_control_msgs::GrabImagesResult PylonCameraNode::grabImagesRaw(
const camera_control_msgs::GrabImagesGoal::ConstPtr& goal,
GrabImagesAS* action_server)
{
camera_control_msgs::GrabImagesResult result;
camera_control_msgs::GrabImagesFeedback feedback;
#if DEBUG
std::cout << *goal << std::endl;
#endif
if ( goal->exposure_given && goal->exposure_times.empty() )
{
ROS_ERROR_STREAM("GrabImagesRaw action server received request and "
<< "'exposure_given' is true, but the 'exposure_times' vector is "
<< "empty! Not enough information to execute acquisition!");
result.success = false;
return result;
}
if ( goal->gain_given && goal->gain_values.empty() )
{
ROS_ERROR_STREAM("GrabImagesRaw action server received request and "
<< "'gain_given' is true, but the 'gain_values' vector is "
<< "empty! Not enough information to execute acquisition!");
result.success = false;
return result;
}
if ( goal->brightness_given && goal->brightness_values.empty() )
{
ROS_ERROR_STREAM("GrabImagesRaw action server received request and "
<< "'brightness_given' is true, but the 'brightness_values' vector"
<< " is empty! Not enough information to execute acquisition!");
result.success = false;
return result;
}
if ( goal->gamma_given && goal->gamma_values.empty() )
{
ROS_ERROR_STREAM("GrabImagesRaw action server received request and "
<< "'gamma_given' is true, but the 'gamma_values' vector is "
<< "empty! Not enough information to execute acquisition!");
result.success = false;
return result;
}
std::vector<size_t> candidates;
candidates.resize(4); // gain, exposure, gamma, brightness
candidates.at(0) = goal->gain_given ? goal->gain_values.size() : 0;
candidates.at(1) = goal->exposure_given ? goal->exposure_times.size() : 0;
candidates.at(2) = goal->brightness_given ? goal->brightness_values.size() : 0;
candidates.at(3) = goal->gamma_given ? goal->gamma_values.size() : 0;
size_t n_images = *std::max_element(candidates.begin(), candidates.end());
if ( goal->exposure_given && goal->exposure_times.size() != n_images )
{
ROS_ERROR_STREAM("Size of requested exposure times does not match to "
<< "the size of the requested vaules of brightness, gain or "
<< "gamma! Can't grab!");
result.success = false;
return result;
}
if ( goal->gain_given && goal->gain_values.size() != n_images )
{
ROS_ERROR_STREAM("Size of requested gain values does not match to "
<< "the size of the requested exposure times or the vaules of "
<< "brightness or gamma! Can't grab!");
result.success = false;
return result;
}
if ( goal->gamma_given && goal->gamma_values.size() != n_images )
{
ROS_ERROR_STREAM("Size of requested gamma values does not match to "
<< "the size of the requested exposure times or the vaules of "
<< "brightness or gain! Can't grab!");
result.success = false;
return result;
}
if ( goal->brightness_given && goal->brightness_values.size() != n_images )
{
ROS_ERROR_STREAM("Size of requested brightness values does not match to "
<< "the size of the requested exposure times or the vaules of gain or "
<< "gamma! Can't grab!");
result.success = false;
return result;
}
if ( goal->brightness_given && !( goal->exposure_auto || goal->gain_auto ) )
{
ROS_ERROR_STREAM("Error while executing the GrabImagesRawAction: A "
<< "target brightness is provided but Exposure time AND gain are "
<< "declared as fix, so its impossible to reach the brightness");
result.success = false;
return result;
}
result.images.resize(n_images);
result.reached_exposure_times.resize(n_images);
result.reached_gain_values.resize(n_images);
result.reached_gamma_values.resize(n_images);
result.reached_brightness_values.resize(n_images);
result.success = true;
boost::lock_guard<boost::recursive_mutex> lock(grab_mutex_);
float previous_exp, previous_gain, previous_gamma;
if ( goal->exposure_given )
{
previous_exp = pylon_camera_->currentExposure();
}
if ( goal->gain_given )
{
previous_gain = pylon_camera_->currentGain();
}
if ( goal->gamma_given )
{
previous_gamma = pylon_camera_->currentGamma();
}
if ( goal->brightness_given )
{
previous_gain = pylon_camera_->currentGain();
previous_exp = pylon_camera_->currentExposure();
}
for ( std::size_t i = 0; i < n_images; ++i )
{
if ( goal->exposure_given )
{
result.success = setExposure(goal->exposure_times[i],
result.reached_exposure_times[i]);
}
if ( goal->gain_given )
{
result.success = setGain(goal->gain_values[i],
result.reached_gain_values[i]);
}
if ( goal->gamma_given )
{
result.success = setGamma(goal->gamma_values[i],
result.reached_gamma_values[i]);
}
if ( goal->brightness_given )
{
int reached_brightness;
result.success = setBrightness(goal->brightness_values[i],
reached_brightness,
goal->exposure_auto,
goal->gain_auto);
result.reached_brightness_values[i] = static_cast<float>(
reached_brightness);
result.reached_exposure_times[i] = pylon_camera_->currentExposure();
result.reached_gain_values[i] = pylon_camera_->currentGain();
}
if ( !result.success )
{
ROS_ERROR_STREAM("Error while setting one of the desired image "
<< "properties in the GrabImagesRawActionCB. Aborting!");
break;
}
sensor_msgs::Image& img = result.images[i];
img.encoding = pylon_camera_->currentROSEncoding();
img.height = pylon_camera_->imageRows();
img.width = pylon_camera_->imageCols();
// step = full row length in bytes, img_size = (step * rows), imagePixelDepth
// already contains the number of channels
img.step = img.width * pylon_camera_->imagePixelDepth();
if ( !pylon_camera_->grab(img.data) )
{
result.success = false;
break;
}
img.header.stamp = ros::Time::now();
img.header.frame_id = cameraFrame();
feedback.curr_nr_images_taken = i+1;
if ( action_server != nullptr )
{
action_server->publishFeedback(feedback);
}
}
// restore previous settings:
float reached_val;
if ( goal->exposure_given )
{
setExposure(previous_exp, reached_val);
}
if ( goal->gain_given )
{
setGain(previous_gain, reached_val);
}
if ( goal->gamma_given )
{
setGamma(previous_gamma, reached_val);
}
if ( goal->brightness_given )
{
setGain(previous_gain, reached_val);
setExposure(previous_exp, reached_val);
}
return result;
}
bool PylonCameraNode::setUserOutputCB(const int output_id,
camera_control_msgs::SetBool::Request &req,
camera_control_msgs::SetBool::Response &res)
{
res.success = pylon_camera_->setUserOutput(output_id, req.data);
return true;
}
const double& PylonCameraNode::frameRate() const
{
return pylon_camera_parameter_set_.frameRate();
}
const std::string& PylonCameraNode::cameraFrame() const
{
return pylon_camera_parameter_set_.cameraFrame();
}
uint32_t PylonCameraNode::getNumSubscribersRect() const
{
return camera_info_manager_->isCalibrated() ? img_rect_pub_->getNumSubscribers() : 0;
}
uint32_t PylonCameraNode::getNumSubscribers() const
{
return img_raw_pub_.getNumSubscribers() + img_rect_pub_->getNumSubscribers();
}
void PylonCameraNode::setupInitialCameraInfo(sensor_msgs::CameraInfo& cam_info_msg)
{
std_msgs::Header header;
header.frame_id = pylon_camera_parameter_set_.cameraFrame();
header.stamp = ros::Time::now();
// http://www.ros.org/reps/rep-0104.html
// If the camera is uncalibrated, the matrices D, K, R, P should be left
// zeroed out. In particular, clients may assume that K[0] == 0.0
// indicates an uncalibrated camera.
cam_info_msg.header = header;
// The image dimensions with which the camera was calibrated. Normally
// this will be the full camera resolution in pixels. They remain fix, even
// if binning is applied
cam_info_msg.height = pylon_camera_->imageRows();
cam_info_msg.width = pylon_camera_->imageCols();
// The distortion model used. Supported models are listed in
// sensor_msgs/distortion_models.h. For most cameras, "plumb_bob" - a
// simple model of radial and tangential distortion - is sufficient.
// Empty D and distortion_model indicate that the CameraInfo cannot be used
// to rectify points or images, either because the camera is not calibrated
// or because the rectified image was produced using an unsupported
// distortion model, e.g. the proprietary one used by Bumblebee cameras
// [http://www.ros.org/reps/rep-0104.html].
cam_info_msg.distortion_model = "";
// The distortion parameters, size depending on the distortion model.
// For "plumb_bob", the 5 parameters are: (k1, k2, t1, t2, k3) -> float64[] D.
cam_info_msg.D = std::vector<double>(5, 0.);
// Intrinsic camera matrix for the raw (distorted) images.
// [fx 0 cx]
// K = [ 0 fy cy] --> 3x3 row-major matrix
// [ 0 0 1]
// Projects 3D points in the camera coordinate frame to 2D pixel coordinates
// using the focal lengths (fx, fy) and principal point (cx, cy).
cam_info_msg.K.assign(0.0);
// Rectification matrix (stereo cameras only)
// A rotation matrix aligning the camera coordinate system to the ideal
// stereo image plane so that epipolar lines in both stereo images are parallel.
cam_info_msg.R.assign(0.0);
// Projection/camera matrix
// [fx' 0 cx' Tx]
// P = [ 0 fy' cy' Ty] --> # 3x4 row-major matrix
// [ 0 0 1 0]
// By convention, this matrix specifies the intrinsic (camera) matrix of the
// processed (rectified) image. That is, the left 3x3 portion is the normal
// camera intrinsic matrix for the rectified image. It projects 3D points
// in the camera coordinate frame to 2D pixel coordinates using the focal
// lengths (fx', fy') and principal point (cx', cy') - these may differ from
// the values in K. For monocular cameras, Tx = Ty = 0. Normally, monocular
// cameras will also have R = the identity and P[1:3,1:3] = K.
// For a stereo pair, the fourth column [Tx Ty 0]' is related to the
// position of the optical center of the second camera in the first
// camera's frame. We assume Tz = 0 so both cameras are in the same
// stereo image plane. The first camera always has Tx = Ty = 0.
// For the right (second) camera of a horizontal stereo pair,
// Ty = 0 and Tx = -fx' * B, where B is the baseline between the cameras.
// Given a 3D point [X Y Z]', the projection (x, y) of the point onto the
// rectified image is given by:
// [u v w]' = P * [X Y Z 1]'
// x = u / w
// y = v / w
// This holds for both images of a stereo pair.
cam_info_msg.P.assign(0.0);
// Binning refers here to any camera setting which combines rectangular
// neighborhoods of pixels into larger "super-pixels." It reduces the
// resolution of the output image to (width / binning_x) x (height / binning_y).
// The default values binning_x = binning_y = 0 is considered the same as
// binning_x = binning_y = 1 (no subsampling).
cam_info_msg.binning_x = pylon_camera_->currentBinningX();
cam_info_msg.binning_y = pylon_camera_->currentBinningY();
// Region of interest (subwindow of full camera resolution), given in full
// resolution (unbinned) image coordinates. A particular ROI always denotes
// the same window of pixels on the camera sensor, regardless of binning
// settings. The default setting of roi (all values 0) is considered the same
// as full resolution (roi.width = width, roi.height = height).
cam_info_msg.roi.x_offset = cam_info_msg.roi.y_offset = 0;
cam_info_msg.roi.height = cam_info_msg.roi.width = 0;
}
/**
* Waits till the pylon_camera_ isReady() observing a given timeout
* @return true when the camera's state toggles to 'isReady()'
*/
bool PylonCameraNode::waitForCamera(const ros::Duration& timeout) const
{
bool result = false;
ros::Time start_time = ros::Time::now();
while ( ros::ok() )
{
if ( pylon_camera_->isReady() )
{
result = true;
break;
}
else
{
if ( timeout >= ros::Duration(0) )
{
if ( ros::Time::now() - start_time >= timeout )
{
ROS_ERROR_STREAM("Setting brightness failed, because the "
<< "interface is not ready. This happens although "
<< "waiting for " << timeout.sec << " seconds!");
return false;
}
}
ros::Duration(0.02).sleep();
}
}
return result;
}
bool PylonCameraNode::setBinningX(const size_t& target_binning_x,
size_t& reached_binning_x)
{
boost::lock_guard<boost::recursive_mutex> lock(grab_mutex_);
if ( !pylon_camera_->setBinningX(target_binning_x, reached_binning_x) )
{
// retry till timeout
ros::Rate r(10.0);
ros::Time timeout(ros::Time::now() + ros::Duration(2.0));
while ( ros::ok() )
{
if ( pylon_camera_->setBinningX(target_binning_x, reached_binning_x) )
{
break;
}
if ( ros::Time::now() > timeout )
{
ROS_ERROR_STREAM("Error in setBinningX(): Unable to set target "
<< "binning_x factor before timeout");
CameraInfoPtr cam_info(new CameraInfo(camera_info_manager_->getCameraInfo()));
cam_info->binning_x = pylon_camera_->currentBinningX();
camera_info_manager_->setCameraInfo(*cam_info);
img_raw_msg_.width = pylon_camera_->imageCols();
// step = full row length in bytes, img_size = (step * rows), imagePixelDepth
// already contains the number of channels
img_raw_msg_.step = img_raw_msg_.width * pylon_camera_->imagePixelDepth();
return false;
}
r.sleep();
}
}
CameraInfoPtr cam_info(new CameraInfo(camera_info_manager_->getCameraInfo()));
cam_info->binning_x = pylon_camera_->currentBinningX();
camera_info_manager_->setCameraInfo(*cam_info);
img_raw_msg_.width = pylon_camera_->imageCols();
// step = full row length in bytes, img_size = (step * rows), imagePixelDepth
// already contains the number of channels
img_raw_msg_.step = img_raw_msg_.width * pylon_camera_->imagePixelDepth();
setupSamplingIndices(sampling_indices_,
pylon_camera_->imageRows(),
pylon_camera_->imageCols(),
pylon_camera_parameter_set_.downsampling_factor_exp_search_);
return true;
}
bool PylonCameraNode::setBinningY(const size_t& target_binning_y,
size_t& reached_binning_y)
{
boost::lock_guard<boost::recursive_mutex> lock(grab_mutex_);
if ( !pylon_camera_->setBinningY(target_binning_y, reached_binning_y) )
{
// retry till timeout
ros::Rate r(10.0);
ros::Time timeout(ros::Time::now() + ros::Duration(2.0));
while ( ros::ok() )
{
if ( pylon_camera_->setBinningY(target_binning_y, reached_binning_y) )
{
break;
}
if ( ros::Time::now() > timeout )
{
ROS_ERROR_STREAM("Error in setBinningY(): Unable to set target "
<< "binning_y factor before timeout");
CameraInfoPtr cam_info(new CameraInfo(camera_info_manager_->getCameraInfo()));
cam_info->binning_y = pylon_camera_->currentBinningY();
camera_info_manager_->setCameraInfo(*cam_info);
img_raw_msg_.height = pylon_camera_->imageRows();
// step = full row length in bytes, img_size = (step * rows), imagePixelDepth
// already contains the number of channels
img_raw_msg_.step = img_raw_msg_.width * pylon_camera_->imagePixelDepth();
return false;
}
r.sleep();
}
}
CameraInfoPtr cam_info(new CameraInfo(camera_info_manager_->getCameraInfo()));
cam_info->binning_y = pylon_camera_->currentBinningY();
camera_info_manager_->setCameraInfo(*cam_info);
img_raw_msg_.height = pylon_camera_->imageRows();
// step = full row length in bytes, img_size = (step * rows), imagePixelDepth
// already contains the number of channels
img_raw_msg_.step = img_raw_msg_.width * pylon_camera_->imagePixelDepth();
setupSamplingIndices(sampling_indices_,
pylon_camera_->imageRows(),
pylon_camera_->imageCols(),
pylon_camera_parameter_set_.downsampling_factor_exp_search_);
return true;
}
bool PylonCameraNode::setBinningCallback(camera_control_msgs::SetBinning::Request &req,
camera_control_msgs::SetBinning::Response &res)
{
size_t reached_binning_x, reached_binning_y;
bool success_x = setBinningX(req.target_binning_x,
reached_binning_x);
bool success_y = setBinningY(req.target_binning_y,
reached_binning_y);
res.reached_binning_x = static_cast<uint32_t>(reached_binning_x);
res.reached_binning_y = static_cast<uint32_t>(reached_binning_y);
res.success = success_x && success_y;
return true;
}
bool PylonCameraNode::setExposure(const float& target_exposure,
float& reached_exposure)
{
boost::lock_guard<boost::recursive_mutex> lock(grab_mutex_);
if ( !pylon_camera_->isReady() )
{
ROS_WARN("Error in setExposure(): pylon_camera_ is not ready!");
return false;
}
if ( pylon_camera_->setExposure(target_exposure, reached_exposure) )
{
// success if the delta is smaller then the exposure step
return true;
}
else // retry till timeout
{
// wait for max 5s till the cam has updated the exposure
ros::Rate r(10.0);
ros::Time timeout(ros::Time::now() + ros::Duration(5.0));
while ( ros::ok() )
{
if ( pylon_camera_->setExposure(target_exposure, reached_exposure) )
{
// success if the delta is smaller then the exposure step
return true;
}
if ( ros::Time::now() > timeout )
{
break;
}
r.sleep();
}