-
Notifications
You must be signed in to change notification settings - Fork 142
/
zed_camera_component.cpp
9390 lines (7884 loc) · 331 KB
/
zed_camera_component.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 2022 Stereolabs
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#include <sstream>
#include <type_traits>
#include <vector>
#include <limits>
#include <sys/resource.h>
#include "zed_camera_component.hpp"
#include "sl_logging.hpp"
#include <diagnostic_msgs/msg/diagnostic_status.hpp>
#include <rcl_interfaces/msg/parameter_descriptor.hpp>
#include <rclcpp/time.hpp>
#include <rclcpp/utilities.hpp>
#include <sensor_msgs/distortion_models.hpp>
#include <sensor_msgs/image_encodings.hpp>
#include <sensor_msgs/msg/point_field.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>
#ifdef FOUND_HUMBLE
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#elif defined FOUND_FOXY
#include <tf2_geometry_msgs/tf2_geometry_msgs.h>
#else
#error Unsupported ROS2 distro
#endif
#include <sl/Camera.hpp>
#include "sl_tools.hpp"
using namespace std::chrono_literals;
using namespace std::placeholders;
// Used for simulation data input
#define ZED_SDK_PORT 30000
namespace stereolabs
{
#ifndef DEG2RAD
#define DEG2RAD 0.017453293
#define RAD2DEG 57.295777937
#endif
#define ROS_COORDINATE_SYSTEM sl::COORDINATE_SYSTEM::RIGHT_HANDED_Z_UP_X_FWD
#define ROS_MEAS_UNITS sl::UNIT::METER
ZedCamera::ZedCamera(const rclcpp::NodeOptions & options)
: Node("zed_node", options),
mVideoQos(1),
mDepthQos(1),
mSensQos(1),
mPoseQos(1),
mMappingQos(1),
mObjDetQos(1),
mBodyTrkQos(1),
mClickedPtQos(1),
mGnssFixQos(1),
mAiInstanceID(0),
mDiagUpdater(this),
mImuTfFreqTimer(get_clock()),
mGrabFreqTimer(get_clock()),
mImuFreqTimer(get_clock()),
mBaroFreqTimer(get_clock()),
mMagFreqTimer(get_clock()),
mOdomFreqTimer(get_clock()),
mPoseFreqTimer(get_clock()),
mPcPubFreqTimer(get_clock()),
mVdPubFreqTimer(get_clock()),
mSensPubFreqTimer(get_clock()),
mOdFreqTimer(get_clock()),
mBtFreqTimer(get_clock()),
mPcFreqTimer(get_clock()),
mGnssFixFreqTimer(get_clock()),
mFrameTimestamp(TIMEZERO_ROS),
mGnssTimestamp(TIMEZERO_ROS),
mLastTs_imu(TIMEZERO_ROS),
mLastTs_baro(TIMEZERO_ROS),
mLastTs_mag(TIMEZERO_ROS),
mLastTs_odom(TIMEZERO_ROS),
mLastTs_pose(TIMEZERO_ROS),
mLastTs_pc(TIMEZERO_ROS),
mPrevTs_pc(TIMEZERO_ROS)
{
RCLCPP_INFO(get_logger(), "********************************");
RCLCPP_INFO(get_logger(), " ZED Camera Component ");
RCLCPP_INFO(get_logger(), "********************************");
RCLCPP_INFO(get_logger(), " * namespace: %s", get_namespace());
RCLCPP_INFO(get_logger(), " * node name: %s", get_name());
RCLCPP_INFO(get_logger(), "********************************");
const size_t SDK_MAJOR_REQ = 4;
const size_t SDK_MINOR_REQ = 0;
if (ZED_SDK_MAJOR_VERSION < SDK_MAJOR_REQ ||
(ZED_SDK_MAJOR_VERSION == SDK_MAJOR_REQ && ZED_SDK_MINOR_VERSION < SDK_MINOR_REQ))
{
RCLCPP_ERROR_STREAM(
get_logger(),
"This version of the ZED ROS2 wrapper is designed to work with ZED SDK v" <<
static_cast<int>(SDK_MAJOR_REQ) << "." << static_cast<int>(SDK_MINOR_REQ) << " or newer.");
RCLCPP_INFO_STREAM(
get_logger(), "* Detected SDK v" << ZED_SDK_MAJOR_VERSION << "." << ZED_SDK_MINOR_VERSION <<
"." << ZED_SDK_PATCH_VERSION << "-" << ZED_SDK_BUILD_ID);
RCLCPP_INFO(get_logger(), "Node stopped");
exit(EXIT_FAILURE);
}
// Parameters initialization
initParameters();
// ----> Diagnostic initialization
mDiagUpdater.add("ZED Diagnostic", this, &ZedCamera::callback_updateDiagnostic);
std::string hw_id = std::string("Stereolabs camera: ") + mCameraName;
mDiagUpdater.setHardwareID(hw_id);
// <---- Diagnostic initialization
// Services initialization
initServices();
// ----> Start camera
if (!startCamera()) {
exit(EXIT_FAILURE);
}
// <---- Start camera
// Dynamic parameters callback
mParamChangeCallbackHandle =
add_on_set_parameters_callback(std::bind(&ZedCamera::callback_paramChange, this, _1));
}
ZedCamera::~ZedCamera()
{
DEBUG_STREAM_COMM("Destroying node");
// ----> Stop subscribers
mClickedPtSub.reset();
mGnssFixSub.reset();
// <---- Stop subscribers
if (mObjDetRunning) {
std::lock_guard<std::mutex> lock(mObjDetMutex);
stopObjDetect();
}
if (mBodyTrkRunning) {
std::lock_guard<std::mutex> lock(mBodyTrkMutex);
stopBodyTracking();
}
if (mSpatialMappingRunning) {
std::lock_guard<std::mutex> lock(mMappingMutex);
stop3dMapping();
}
DEBUG_STREAM_PT("Stopping path timer");
if (mPathTimer) {
mPathTimer->cancel();
}
DEBUG_STREAM_MAP("Stopping fused cloud timer");
if (mFusedPcTimer) {
mFusedPcTimer->cancel();
}
DEBUG_STREAM_SENS("Stopping temperatures timer");
if (mTempPubTimer) {
mTempPubTimer->cancel();
}
// ----> Verify that all the threads are not active
DEBUG_STREAM_COMM("Stopping running threads");
if (!mThreadStop) {
mThreadStop = true;
}
DEBUG_STREAM_COMM("Waiting for grab thread...");
try {
if (mGrabThread.joinable()) {
mGrabThread.join();
}
} catch (std::system_error & e) {
DEBUG_STREAM_COMM("Grab thread joining exception: " << e.what());
}
DEBUG_STREAM_COMM("... grab thread stopped");
DEBUG_STREAM_SENS("Waiting for sensors thread...");
try {
if (mSensThread.joinable()) {
mSensThread.join();
}
} catch (std::system_error & e) {
DEBUG_STREAM_SENS("Sensors thread joining exception: " << e.what());
}
DEBUG_STREAM_SENS("... sensors thread stopped");
DEBUG_STREAM_VD("Waiting for RGB/Depth thread...");
try {
if (mVideoDepthThread.joinable()) {
mVideoDepthThread.join();
}
} catch (std::system_error & e) {
DEBUG_STREAM_VD("RGB/Depth thread joining exception: " << e.what());
}
DEBUG_STREAM_VD("... RGB/Depth thread stopped");
DEBUG_STREAM_PC("Waiting for Point Cloud thread...");
try {
if (mPcThread.joinable()) {
mPcThread.join();
}
} catch (std::system_error & e) {
DEBUG_STREAM_PC("Pointcloud thread joining exception: " << e.what());
}
DEBUG_STREAM_PC("... Point Cloud thread stopped");
// <---- Verify that all the threads are not active
}
void ZedCamera::initServices()
{
RCLCPP_INFO(get_logger(), "*** SERVICES ***");
std::string srv_name;
std::string srv_prefix = "~/";
if (!mDepthDisabled) {
// ResetOdometry
srv_name = srv_prefix + mSrvResetOdomName;
mResetOdomSrv = create_service<std_srvs::srv::Trigger>(
srv_name, std::bind(&ZedCamera::callback_resetOdometry, this, _1, _2, _3));
RCLCPP_INFO(get_logger(), " * '%s'", mResetOdomSrv->get_service_name());
srv_name = srv_prefix + mSrvResetPoseName;
mResetPosTrkSrv = create_service<std_srvs::srv::Trigger>(
srv_name, std::bind(&ZedCamera::callback_resetPosTracking, this, _1, _2, _3));
RCLCPP_INFO(get_logger(), " * '%s'", mResetPosTrkSrv->get_service_name());
srv_name = srv_prefix + mSrvSetPoseName;
mSetPoseSrv = create_service<zed_interfaces::srv::SetPose>(
srv_name, std::bind(&ZedCamera::callback_setPose, this, _1, _2, _3));
RCLCPP_INFO(get_logger(), " * '%s'", mSetPoseSrv->get_service_name());
srv_name = srv_prefix + mSrvEnableObjDetName;
mEnableObjDetSrv = create_service<std_srvs::srv::SetBool>(
srv_name, std::bind(&ZedCamera::callback_enableObjDet, this, _1, _2, _3));
RCLCPP_INFO(get_logger(), " * '%s'", mEnableObjDetSrv->get_service_name());
srv_name = srv_prefix + mSrvEnableBodyTrkName;
mEnableBodyTrkSrv = create_service<std_srvs::srv::SetBool>(
srv_name, std::bind(&ZedCamera::callback_enableBodyTrk, this, _1, _2, _3));
RCLCPP_INFO(get_logger(), " * '%s'", mEnableBodyTrkSrv->get_service_name());
srv_name = srv_prefix + mSrvEnableMappingName;
mEnableMappingSrv = create_service<std_srvs::srv::SetBool>(
srv_name, std::bind(&ZedCamera::callback_enableMapping, this, _1, _2, _3));
RCLCPP_INFO(get_logger(), " * '%s'", mEnableMappingSrv->get_service_name());
}
srv_name = srv_prefix + mSrvStartSvoRecName;
mStartSvoRecSrv = create_service<zed_interfaces::srv::StartSvoRec>(
srv_name, std::bind(&ZedCamera::callback_startSvoRec, this, _1, _2, _3));
RCLCPP_INFO(get_logger(), " * '%s'", mStartSvoRecSrv->get_service_name());
srv_name = srv_prefix + mSrvStopSvoRecName;
mStopSvoRecSrv = create_service<std_srvs::srv::Trigger>(
srv_name, std::bind(&ZedCamera::callback_stopSvoRec, this, _1, _2, _3));
RCLCPP_INFO(get_logger(), " * '%s'", mStopSvoRecSrv->get_service_name());
if (mSvoMode && !mSvoRealtime) {
srv_name = srv_prefix + mSrvToggleSvoPauseName;
mPauseSvoSrv = create_service<std_srvs::srv::Trigger>(
srv_name, std::bind(&ZedCamera::callback_pauseSvoInput, this, _1, _2, _3));
RCLCPP_INFO(get_logger(), " * '%s'", mPauseSvoSrv->get_service_name());
}
srv_name = srv_prefix + mSrvSetRoiName;
mSetRoiSrv = create_service<zed_interfaces::srv::SetROI>(
srv_name, std::bind(&ZedCamera::callback_setRoi, this, _1, _2, _3));
RCLCPP_INFO(get_logger(), " * '%s'", mSetRoiSrv->get_service_name());
srv_name = srv_prefix + mSrvResetRoiName;
mResetRoiSrv = create_service<std_srvs::srv::Trigger>(
srv_name, std::bind(&ZedCamera::callback_resetRoi, this, _1, _2, _3));
RCLCPP_INFO(get_logger(), " * '%s'", mResetRoiSrv->get_service_name());
if (mGnssFusionEnabled) {
srv_name = srv_prefix + mSrvToLlName;
mToLlSrv = create_service<robot_localization::srv::ToLL>(
srv_name, std::bind(&ZedCamera::callback_toLL, this, _1, _2, _3));
RCLCPP_INFO(get_logger(), " * '%s'", mToLlSrv->get_service_name());
srv_name = srv_prefix + mSrvFromLlName;
mFromLlSrv = create_service<robot_localization::srv::FromLL>(
srv_name, std::bind(&ZedCamera::callback_fromLL, this, _1, _2, _3));
RCLCPP_INFO(get_logger(), " * '%s'", mFromLlSrv->get_service_name());
}
}
std::string ZedCamera::getParam(std::string paramName, std::vector<std::vector<float>> & outVal)
{
outVal.clear();
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.read_only = true;
declare_parameter(paramName, rclcpp::ParameterValue(std::string("[]")), descriptor);
std::string out_str;
if (!get_parameter(paramName, out_str)) {
RCLCPP_WARN_STREAM(
get_logger(), "The parameter '" << paramName <<
"' is not available or is not valid, using the default "
"value: []");
}
if (out_str.empty()) {
return std::string();
}
std::string error;
outVal = sl_tools::parseStringVector(out_str, error);
if (error != "") {
RCLCPP_WARN_STREAM(
get_logger(), "Error parsing " << paramName << " parameter: " << error.c_str());
RCLCPP_WARN_STREAM(get_logger(), " " << paramName << " string was " << out_str.c_str());
outVal.clear();
}
return out_str;
}
template<typename T>
void ZedCamera::getParam(
std::string paramName, T defValue, T & outVal, std::string log_info, bool dynamic)
{
rcl_interfaces::msg::ParameterDescriptor descriptor;
descriptor.read_only = !dynamic;
declare_parameter(paramName, rclcpp::ParameterValue(defValue), descriptor);
if (!get_parameter(paramName, outVal)) {
RCLCPP_WARN_STREAM(
get_logger(), "The parameter '" <<
paramName <<
"' is not available or is not valid, using the default value: " <<
defValue);
}
if (!log_info.empty()) {
RCLCPP_INFO_STREAM(get_logger(), log_info << outVal);
}
}
void ZedCamera::initParameters()
{
// DEBUG parameters
getDebugParams();
// SIMULATION parameters
getSimParams();
// GENERAL parameters
getGeneralParams();
// VIDEO parameters
getVideoParams();
// DEPTH parameters
getDepthParams();
// POS. TRACKING and GNSS FUSION parameters
if (!mDepthDisabled) {
getGnssFusionParams();
getPosTrackingParams();
} else {
mGnssFusionEnabled = false;
mPosTrackingEnabled = false;
}
// SENSORS parameters
if (!sl_tools::isZED(mCamUserModel)) {
getSensorsParams();
}
if (!mDepthDisabled) {
getMappingParams();
} else {
mMappingEnabled = false;
}
// AI PARAMETERS
if (!mDepthDisabled) {
if (sl_tools::isObjDetAvailable(mCamUserModel)) {
getOdParams();
getBodyTrkParams();
}
} else {
mObjDetEnabled = false;
mBodyTrkEnabled = false;
}
getAdvancedParams();
}
std::string ZedCamera::parseRoiPoly(
const std::vector<std::vector<float>> & in_poly, std::vector<sl::float2> & out_poly)
{
out_poly.clear();
std::string ss;
ss = "[";
size_t poly_size = in_poly.size();
if (poly_size < 3) {
if (poly_size != 0) {
RCLCPP_WARN_STREAM(
get_logger(), "A vector with " <<
poly_size <<
" points is not enough to create a polygon to set a Region "
"of Interest.");
return std::string();
}
} else {
for (size_t i; i < poly_size; ++i) {
if (in_poly[i].size() != 2) {
RCLCPP_WARN_STREAM(
get_logger(), "The component with index '" << i <<
"' of the ROI vector "
"has not the correct size.");
out_poly.clear();
return std::string();
} else if (in_poly[i][0] < 0.0 || in_poly[i][1] < 0.0 || in_poly[i][0] > 1.0 ||
in_poly[i][1] > 1.0)
{
RCLCPP_WARN_STREAM(
get_logger(), "The component with index '" << i <<
"' of the ROI vector "
"is not a "
"valid normalized point: [" <<
in_poly[i][0] << "," << in_poly[i][1] <<
"].");
out_poly.clear();
return std::string();
} else {
sl::float2 pt;
pt.x = in_poly[i][0];
pt.y = in_poly[i][1];
out_poly.push_back(pt);
ss += "[";
ss += std::to_string(pt.x);
ss += ",";
ss += std::to_string(pt.y);
ss += "]";
}
if (i != poly_size - 1) {
ss += ",";
}
}
}
ss += "]";
return ss;
}
void ZedCamera::getDebugParams()
{
rclcpp::Parameter paramVal;
std::string paramName;
RCLCPP_INFO(get_logger(), "*** DEBUG parameters ***");
getParam("debug.debug_common", mDebugCommon, mDebugCommon);
RCLCPP_INFO(get_logger(), " * Debug Common: %s", mDebugCommon ? "TRUE" : "FALSE");
getParam("debug.debug_video_depth", mDebugVideoDepth, mDebugVideoDepth);
RCLCPP_INFO(get_logger(), " * Debug Video/Depth: %s", mDebugVideoDepth ? "TRUE" : "FALSE");
getParam("debug.debug_camera_controls", mDebugCamCtrl, mDebugCamCtrl);
RCLCPP_INFO(get_logger(), " * Debug Control settings: %s", mDebugCamCtrl ? "TRUE" : "FALSE");
getParam("debug.debug_point_cloud", mDebugPointCloud, mDebugPointCloud);
RCLCPP_INFO(get_logger(), " * Debug Point Cloud: %s", mDebugPointCloud ? "TRUE" : "FALSE");
getParam("debug.debug_gnss", mDebugGnss, mDebugGnss);
RCLCPP_INFO(
get_logger(), " * Debug GNSS: %s",
mDebugGnss ? "TRUE" : "FALSE");
getParam("debug.debug_positional_tracking", mDebugPosTracking, mDebugPosTracking);
RCLCPP_INFO(
get_logger(), " * Debug Positional Tracking: %s",
mDebugPosTracking ? "TRUE" : "FALSE");
getParam("debug.debug_sensors", mDebugSensors, mDebugSensors);
RCLCPP_INFO(get_logger(), " * Debug sensors: %s", mDebugSensors ? "TRUE" : "FALSE");
getParam("debug.debug_mapping", mDebugMapping, mDebugMapping);
RCLCPP_INFO(get_logger(), " * Debug Mapping: %s", mDebugMapping ? "TRUE" : "FALSE");
getParam("debug.debug_object_detection", mDebugObjectDet, mDebugObjectDet);
RCLCPP_INFO(
get_logger(), " * Debug Object Detection: %s",
mDebugObjectDet ? "TRUE" : "FALSE");
getParam("debug.debug_body_tracking", mDebugBodyTrk, mDebugBodyTrk);
RCLCPP_INFO(
get_logger(), " * Debug Body Tracking: %s",
mDebugBodyTrk ? "TRUE" : "FALSE");
getParam("debug.debug_advanced", mDebugAdvanced, mDebugAdvanced);
RCLCPP_INFO(get_logger(), " * Debug Advanced: %s", mDebugAdvanced ? "TRUE" : "FALSE");
mDebugMode = mDebugCommon || mDebugVideoDepth || mDebugCamCtrl || mDebugPointCloud ||
mDebugPosTracking || mDebugGnss || mDebugSensors || mDebugMapping ||
mDebugObjectDet || mDebugBodyTrk || mDebugAdvanced;
if (mDebugMode) {
rcutils_ret_t res =
rcutils_logging_set_logger_level(get_logger().get_name(), RCUTILS_LOG_SEVERITY_DEBUG);
if (res != RCUTILS_RET_OK) {
RCLCPP_INFO(get_logger(), "Error setting DEBUG level for logger");
} else {
RCLCPP_INFO(get_logger(), " + Debug Mode enabled +");
}
} else {
rcutils_ret_t res =
rcutils_logging_set_logger_level(get_logger().get_name(), RCUTILS_LOG_SEVERITY_INFO);
if (res != RCUTILS_RET_OK) {
RCLCPP_INFO(get_logger(), "Error setting INFO level for logger");
}
}
DEBUG_STREAM_COMM("[ROS2] Using RMW_IMPLEMENTATION " << rmw_get_implementation_identifier());
}
void ZedCamera::getSimParams()
{
// SIMULATION active?
if (!get_parameter("use_sim_time", mSimEnabled)) {
RCLCPP_WARN_STREAM(
get_logger(),
"The parameter 'use_sim_time' is not available or is not valid, using the default value: " <<
mSimEnabled);
}
if (mSimEnabled) {
RCLCPP_INFO(get_logger(), " *** SIMULATION MODE ACTIVE ***");
getParam("sim_address", mSimAddr, mSimAddr, " * Simulator address: ");
}
}
void ZedCamera::getGeneralParams()
{
rclcpp::Parameter paramVal;
std::string paramName;
RCLCPP_INFO(get_logger(), "*** GENERAL parameters ***");
getParam("general.svo_file", std::string(), mSvoFilepath);
if (mSvoFilepath.compare("live") == 0) {
mSvoFilepath = "";
}
RCLCPP_INFO_STREAM(get_logger(), " * SVO: '" << mSvoFilepath.c_str() << "'");
if (mSvoFilepath == "") {
mSvoMode = false;
} else {
mSvoMode = true;
getParam("general.svo_loop", mSvoLoop, mSvoLoop);
RCLCPP_INFO(get_logger(), " * SVO Loop: %s", mSvoLoop ? "TRUE" : "FALSE");
getParam("general.svo_realtime", mSvoRealtime, mSvoRealtime);
RCLCPP_INFO(get_logger(), " * SVO Realtime: %s", mSvoRealtime ? "TRUE" : "FALSE");
}
std::string camera_model = "zed";
getParam("general.camera_model", camera_model, camera_model);
if (camera_model == "zed") {
mCamUserModel = sl::MODEL::ZED;
} else if (camera_model == "zedm") {
mCamUserModel = sl::MODEL::ZED_M;
} else if (camera_model == "zed2") {
mCamUserModel = sl::MODEL::ZED2;
} else if (camera_model == "zed2i") {
mCamUserModel = sl::MODEL::ZED2i;
} else if (camera_model == "zedx") {
mCamUserModel = sl::MODEL::ZED_X;
if (mSvoMode) {
RCLCPP_INFO_STREAM(
get_logger(), " + Playing an SVO for " << sl::toString(
mCamUserModel) << " camera model.");
} else if (mSimEnabled) {
RCLCPP_INFO_STREAM(
get_logger(), " + Simulating a " << sl::toString(
mCamUserModel) << " camera model.");
} else if (!IS_JETSON) {
RCLCPP_ERROR_STREAM(
get_logger(), "Camera model " << sl::toString(
mCamUserModel).c_str() << " is available only with NVIDIA Jetson devices.");
exit(EXIT_FAILURE);
}
} else if (camera_model == "zedxm") {
mCamUserModel = sl::MODEL::ZED_XM;
if (mSvoMode) {
RCLCPP_INFO_STREAM(
get_logger(), " + Playing an SVO for " << sl::toString(
mCamUserModel) << " camera model.");
} else if (mSimEnabled) {
RCLCPP_INFO_STREAM(
get_logger(), " + Simulating a " << sl::toString(
mCamUserModel) << " camera model.");
} else if (!IS_JETSON) {
RCLCPP_ERROR_STREAM(
get_logger(), "Camera model " << sl::toString(
mCamUserModel).c_str() << " is available only with NVIDIA Jetson devices.");
exit(EXIT_FAILURE);
}
} else {
RCLCPP_ERROR_STREAM(
get_logger(), "Camera model not valid in parameter values: " << camera_model);
}
RCLCPP_INFO_STREAM(get_logger(), " * Camera model: " << camera_model << " - " << mCamUserModel);
getParam("general.sdk_verbose", mVerbose, mVerbose, " * SDK Verbose: ");
getParam("general.camera_name", mCameraName, mCameraName, " * Camera name: ");
getParam("general.zed_id", mCamId, mCamId, " * Camera ID: ");
getParam("general.serial_number", mCamSerialNumber, mCamSerialNumber, " * Camera SN: ");
getParam(
"general.camera_timeout_sec", mCamTimeoutSec, mCamTimeoutSec, " * Camera timeout [sec]: ");
getParam(
"general.camera_max_reconnect", mMaxReconnectTemp, mMaxReconnectTemp,
" * Camera reconnection temptatives: ");
getParam(
"general.grab_frame_rate", mCamGrabFrameRate, mCamGrabFrameRate, " * Camera framerate: ");
getParam("general.gpu_id", mGpuId, mGpuId, " * GPU ID: ");
// TODO(walter) ADD SVO SAVE COMPRESSION PARAMETERS
std::string resol = "AUTO";
getParam("general.grab_resolution", resol, resol);
if (resol == "AUTO") {
mCamResol = sl::RESOLUTION::AUTO;
} else if (sl_tools::isZEDX(mCamUserModel)) {
if (resol == "HD1200") {
mCamResol = sl::RESOLUTION::HD1200;
} else if (resol == "HD1080") {
mCamResol = sl::RESOLUTION::HD1080;
} else if (resol == "SVGA") {
mCamResol = sl::RESOLUTION::SVGA;
} else {
RCLCPP_WARN(
get_logger(),
"Not valid 'general.grab_resolution' value: '%s'. Using 'AUTO' setting.", resol.c_str());
mCamResol = sl::RESOLUTION::AUTO;
}
RCLCPP_INFO_STREAM(
get_logger(), " * Camera resolution: " << sl::toString(mCamResol).c_str());
} else {
if (resol == "HD2K") {
mCamResol = sl::RESOLUTION::HD2K;
} else if (resol == "HD1080") {
mCamResol = sl::RESOLUTION::HD1080;
} else if (resol == "HD720") {
mCamResol = sl::RESOLUTION::HD720;
} else if (resol == "VGA") {
mCamResol = sl::RESOLUTION::VGA;
} else {
RCLCPP_WARN(
get_logger(),
"Not valid 'general.grab_resolution' value: '%s'. Using 'AUTO' setting.", resol.c_str());
mCamResol = sl::RESOLUTION::AUTO;
}
RCLCPP_INFO_STREAM(
get_logger(), " * Camera resolution: " << sl::toString(mCamResol).c_str());
}
std::string out_resol = "MEDIUM";
getParam("general.pub_resolution", out_resol, out_resol);
if (out_resol == "NATIVE") {
mPubResolution = PubRes::NATIVE;
} else if (out_resol == "CUSTOM") {
mPubResolution = PubRes::CUSTOM;
} else {
RCLCPP_WARN(
get_logger(), "Not valid 'general.pub_resolution' value: '%s'. Using default setting instead.",
out_resol.c_str());
out_resol = "NATIVE";
mPubResolution = PubRes::NATIVE;
}
RCLCPP_INFO_STREAM(get_logger(), " * Publishing resolution: " << out_resol.c_str());
if (mPubResolution == PubRes::CUSTOM) {
getParam(
"general.pub_downscale_factor", mCustomDownscaleFactor, mCustomDownscaleFactor,
" * Publishing downscale factor: ");
} else {
mCustomDownscaleFactor = 1.0;
}
std::string parsed_str = getParam("general.region_of_interest", mRoiParam);
RCLCPP_INFO_STREAM(get_logger(), " * Region of interest: " << parsed_str.c_str());
getParam("general.self_calib", mCameraSelfCalib, mCameraSelfCalib);
RCLCPP_INFO_STREAM(
get_logger(), " * Camera self calibration: " << (mCameraSelfCalib ? "TRUE" : "FALSE"));
getParam("general.camera_flip", mCameraFlip, mCameraFlip);
RCLCPP_INFO_STREAM(get_logger(), " * Camera flip: " << (mCameraFlip ? "TRUE" : "FALSE"));
// Dynamic parameters
getParam("general.pub_frame_rate", mPubFrameRate, mPubFrameRate, "", false);
if (mPubFrameRate > mCamGrabFrameRate) {
RCLCPP_WARN(get_logger(), "'pub_frame_rate' cannot be bigger than 'grab_frame_rate'");
mPubFrameRate = mCamGrabFrameRate;
}
if (mPubFrameRate < 0.1) {
RCLCPP_WARN(get_logger(), "'pub_frame_rate' cannot be lower than 0.1 Hz or negative.");
mPubFrameRate = mCamGrabFrameRate;
}
RCLCPP_INFO_STREAM(get_logger(), " * [DYN] Publish framerate [Hz]: " << mPubFrameRate);
}
void ZedCamera::getVideoParams()
{
rclcpp::Parameter paramVal;
std::string paramName;
RCLCPP_INFO(get_logger(), "*** VIDEO parameters ***");
rmw_qos_history_policy_t qos_hist = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
int qos_depth = 1;
rmw_qos_reliability_policy_t qos_reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
rmw_qos_durability_policy_t qos_durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
rcl_interfaces::msg::ParameterDescriptor read_only_descriptor;
read_only_descriptor.read_only = true;
if (!sl_tools::isZEDX(mCamUserModel)) {
getParam("video.brightness", mCamBrightness, mCamBrightness, " * [DYN] Brightness: ", true);
getParam("video.contrast", mCamContrast, mCamContrast, " * [DYN] Contrast: ", true);
getParam("video.hue", mCamHue, mCamHue, " * [DYN] Hue: ", true);
}
getParam("video.saturation", mCamSaturation, mCamSaturation, " * [DYN] Saturation: ", true);
getParam("video.sharpness", mCamSharpness, mCamSharpness, " * [DYN] Sharpness: ", true);
getParam("video.gamma", mCamGamma, mCamGamma, " * [DYN] Gamma: ", true);
getParam("video.auto_exposure_gain", mCamAutoExpGain, mCamAutoExpGain, "", true);
RCLCPP_INFO(get_logger(), " * [DYN] Auto Exposure/Gain: %s", mCamAutoExpGain ? "TRUE" : "FALSE");
if (mCamAutoExpGain) {
mTriggerAutoExpGain = true;
}
getParam("video.exposure", mCamExposure, mCamExposure, " * [DYN] Exposure: ", true);
getParam("video.gain", mCamGain, mCamGain, " * [DYN] Gain: ", true);
getParam("video.auto_whitebalance", mCamAutoWB, mCamAutoWB, "", true);
RCLCPP_INFO(get_logger(), " * [DYN] Auto White Balance: %s", mCamAutoWB ? "TRUE" : "FALSE");
if (mCamAutoWB) {
mTriggerAutoWB = true;
}
int wb = 42;
getParam("video.whitebalance_temperature", wb, wb, " * [DYN] White Balance Temperature: ", true);
mCamWBTemp = wb * 100;
if (sl_tools::isZEDX(mCamUserModel)) {
getParam(
"video.exposure_time", mGmslExpTime, mGmslExpTime, " * [DYN] ZED X Exposure time: ",
true);
getParam(
"video.auto_exposure_time_range_min", mGmslAutoExpTimeRangeMin,
mGmslAutoExpTimeRangeMin, " * [DYN] ZED X Auto Exp. time range min: ", true);
getParam(
"video.auto_exposure_time_range_max", mGmslAutoExpTimeRangeMax,
mGmslAutoExpTimeRangeMax, " * [DYN] ZED X Auto Exp. time range max: ", true);
if (mGmslAutoExpTimeRangeMax > mCamGrabFrameRate * 1000 || mGmslAutoExpTimeRangeMax > 30000) {
mGmslAutoExpTimeRangeMax = std::max(mCamGrabFrameRate * 1000, 30000);
RCLCPP_WARN_STREAM(
get_logger(),
"The values of 'video.auto_exposure_time_range_max' is clamped to max(30000,'general.grab_frame_rate'x1000): " <<
mGmslAutoExpTimeRangeMax);
}
getParam(
"video.exposure_compensation", mGmslExposureComp, mGmslExposureComp,
" * [DYN] ZED X Exposure comp.: ", true);
getParam(
"video.analog_gain", mGmslAnalogGain, mGmslAnalogGain, " * [DYN] ZED X Analog Gain: ",
true);
getParam(
"video.auto_analog_gain_range_min", mGmslAnalogGainRangeMin, mGmslAnalogGainRangeMin,
" * [DYN] ZED X Auto Analog Gain range min: ", true);
getParam(
"video.auto_analog_gain_range_max", mGmslAnalogGainRangeMax, mGmslAnalogGainRangeMax,
" * [DYN] ZED X Auto Analog Gain range max: ", true);
getParam(
"video.digital_gain", mGmslDigitalGain, mGmslDigitalGain,
" * [DYN] ZED X Digital Gain: ", true);
getParam(
"video.auto_digital_gain_range_min", mGmslAutoDigitalGainRangeMin,
mGmslAutoDigitalGainRangeMin, " * [DYN] ZED X Auto Digital Gain range min: ", true);
getParam(
"video.auto_digital_gain_range_max", mGmslAutoDigitalGainRangeMax,
mGmslAutoDigitalGainRangeMax, " * [DYN] ZED X Auto Digital Gain range max: ", true);
getParam(
"video.denoising", mGmslDenoising, mGmslDenoising,
" * [DYN] ZED X Auto Digital Gain range max: ", true);
}
// ------------------------------------------
paramName = "video.qos_history";
declare_parameter(paramName, rclcpp::ParameterValue(qos_hist), read_only_descriptor);
if (get_parameter(paramName, paramVal)) {
qos_hist =
paramVal.as_int() == 1 ? RMW_QOS_POLICY_HISTORY_KEEP_LAST : RMW_QOS_POLICY_HISTORY_KEEP_ALL;
mVideoQos.history(qos_hist);
} else {
RCLCPP_WARN(
get_logger(), "The parameter '%s' is not available, using the default value",
paramName.c_str());
}
RCLCPP_INFO(get_logger(), " * Video QoS History: %s", sl_tools::qos2str(qos_hist).c_str());
// ------------------------------------------
paramName = "video.qos_depth";
declare_parameter(paramName, rclcpp::ParameterValue(qos_depth), read_only_descriptor);
if (get_parameter(paramName, paramVal)) {
qos_depth = paramVal.as_int();
mVideoQos.keep_last(qos_depth);
} else {
RCLCPP_WARN(
get_logger(), "The parameter '%s' is not available, using the default value",
paramName.c_str());
}
RCLCPP_INFO(get_logger(), " * Video QoS History depth: %d", qos_depth);
// ------------------------------------------
paramName = "video.qos_reliability";
declare_parameter(paramName, rclcpp::ParameterValue(qos_reliability), read_only_descriptor);
if (get_parameter(paramName, paramVal)) {
qos_reliability = paramVal.as_int() == 1 ? RMW_QOS_POLICY_RELIABILITY_RELIABLE :
RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
mVideoQos.reliability(qos_reliability);
} else {
RCLCPP_WARN(
get_logger(), "The parameter '%s' is not available, using the default value",
paramName.c_str());
}
RCLCPP_INFO(
get_logger(), " * Video QoS Reliability: %s", sl_tools::qos2str(qos_reliability).c_str());
// ------------------------------------------
paramName = "video.qos_durability";
declare_parameter(paramName, rclcpp::ParameterValue(qos_durability), read_only_descriptor);
if (get_parameter(paramName, paramVal)) {
qos_durability = paramVal.as_int() == 0 ? RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL :
RMW_QOS_POLICY_DURABILITY_VOLATILE;
mVideoQos.durability(qos_durability);
} else {
RCLCPP_WARN(
get_logger(), "The parameter '%s' is not available, using the default value",
paramName.c_str());
}
RCLCPP_INFO(
get_logger(), " * Video QoS Durability: %s", sl_tools::qos2str(qos_durability).c_str());
}
void ZedCamera::getDepthParams()
{
rclcpp::Parameter paramVal;
std::string paramName;
rmw_qos_history_policy_t qos_hist = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
int qos_depth = 1;
rmw_qos_reliability_policy_t qos_reliability = RMW_QOS_POLICY_RELIABILITY_RELIABLE;
rmw_qos_durability_policy_t qos_durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
rcl_interfaces::msg::ParameterDescriptor read_only_descriptor;
read_only_descriptor.read_only = true;
RCLCPP_INFO(get_logger(), "*** DEPTH parameters ***");
std::string depth_mode_str = sl::toString(mDepthMode).c_str();
getParam("depth.depth_mode", depth_mode_str, depth_mode_str);
bool matched = false;
for (int mode = static_cast<int>(sl::DEPTH_MODE::NONE);
mode < static_cast<int>(sl::DEPTH_MODE::LAST); ++mode)
{
std::string test_str = sl::toString(static_cast<sl::DEPTH_MODE>(mode)).c_str();
std::replace(test_str.begin(), test_str.end(), ' ', '_'); // Replace spaces with underscores to match the YAML setting
if (test_str == depth_mode_str) {
matched = true;
mDepthMode = static_cast<sl::DEPTH_MODE>(mode);
break;
}
}
if (!matched) {
RCLCPP_WARN(
get_logger(),
"The parameter 'depth.depth_mode' contains a not valid string. Please check it in 'common.yaml'.");
RCLCPP_WARN(get_logger(), "Using default DEPTH_MODE.");
mDepthMode = sl::DEPTH_MODE::PERFORMANCE;
}
if (mDepthMode == sl::DEPTH_MODE::NONE) {
mDepthDisabled = true;
mDepthStabilization = 0;
RCLCPP_INFO_STREAM(
get_logger(),
" * Depth mode: " << sl::toString(mDepthMode).c_str() << " - DEPTH DISABLED");
} else {
mDepthDisabled = false;
RCLCPP_INFO_STREAM(
get_logger(), " * Depth mode: " << sl::toString(
mDepthMode).c_str() << " [" << static_cast<int>(mDepthMode) << "]");
}
if (!mDepthDisabled) {
getParam("depth.min_depth", mCamMinDepth, mCamMinDepth, " * Min depth [m]: ");
getParam("depth.max_depth", mCamMaxDepth, mCamMaxDepth, " * Max depth [m]: ");
getParam(
"depth.depth_stabilization", mDepthStabilization, mDepthStabilization,
" * Depth Stabilization: ");
if (mDepthStabilization < 0 || mDepthStabilization > 100) {
mDepthStabilization = 1;
RCLCPP_WARN_STREAM(
get_logger(),
"'depth.depth_stabilization' is not in the valid range [0,100]. Using the default value.");
}
getParam("depth.openni_depth_mode", mOpenniDepthMode, mOpenniDepthMode);
RCLCPP_INFO(
get_logger(), " * OpenNI mode (16bit point cloud): %s", mOpenniDepthMode ? "TRUE" : "FALSE");
getParam("depth.point_cloud_freq", mPcPubRate, mPcPubRate, "", true);
if (mPcPubRate > mPubFrameRate) {
RCLCPP_WARN(get_logger(), "'point_cloud_freq' cannot be bigger than 'pub_frame_rate'");
mPcPubRate = mPubFrameRate;
}
if (mPcPubRate < 0.1) {
RCLCPP_WARN(get_logger(), "'point_cloud_freq' cannot be lower than 0.1 Hz or negative.");
mPcPubRate = mPubFrameRate;
}
RCLCPP_INFO_STREAM(get_logger(), " * [DYN] Point cloud rate [Hz]: " << mPcPubRate);
getParam("depth.depth_confidence", mDepthConf, mDepthConf, " * [DYN] Depth Confidence: ", true);
getParam(
"depth.depth_texture_conf", mDepthTextConf, mDepthTextConf,
" * [DYN] Depth Texture Confidence: ", true);
getParam("depth.remove_saturated_areas", mRemoveSatAreas, mRemoveSatAreas, "", true);
RCLCPP_INFO(
get_logger(), " * [DYN] Remove saturated areas: %s", mRemoveSatAreas ? "TRUE" : "FALSE");
// ------------------------------------------
paramName = "depth.qos_history";
declare_parameter(paramName, rclcpp::ParameterValue(qos_hist), read_only_descriptor);
if (get_parameter(paramName, paramVal)) {
qos_hist =
paramVal.as_int() == 1 ? RMW_QOS_POLICY_HISTORY_KEEP_LAST : RMW_QOS_POLICY_HISTORY_KEEP_ALL;
mDepthQos.history(qos_hist);
} else {
RCLCPP_WARN(
get_logger(), "The parameter '%s' is not available, using the default value",
paramName.c_str());
}
RCLCPP_INFO(get_logger(), " * Depth QoS History: %s", sl_tools::qos2str(qos_hist).c_str());