-
Notifications
You must be signed in to change notification settings - Fork 1.8k
/
base_realsense_node.cpp
2579 lines (2327 loc) · 103 KB
/
base_realsense_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
#include "realsense2_camera/base_realsense_node.h"
#include "assert.h"
#include <boost/algorithm/string.hpp>
#include <algorithm>
#include <cctype>
#include <mutex>
#include <dynamic_reconfigure/IntParameter.h>
#include <dynamic_reconfigure/Reconfigure.h>
#include <dynamic_reconfigure/Config.h>
using namespace realsense2_camera;
using namespace ddynamic_reconfigure;
// stream_index_pair sip{stream_type, stream_index};
#define STREAM_NAME(sip) (static_cast<std::ostringstream&&>(std::ostringstream() << _stream_name[sip.first] << ((sip.second>0) ? std::to_string(sip.second) : ""))).str()
#define FRAME_ID(sip) (static_cast<std::ostringstream&&>(std::ostringstream() << "camera_" << STREAM_NAME(sip) << "_frame")).str()
#define OPTICAL_FRAME_ID(sip) (static_cast<std::ostringstream&&>(std::ostringstream() << "camera_" << STREAM_NAME(sip) << "_optical_frame")).str()
#define ALIGNED_DEPTH_TO_FRAME_ID(sip) (static_cast<std::ostringstream&&>(std::ostringstream() << "camera_aligned_depth_to_" << STREAM_NAME(sip) << "_frame")).str()
SyncedImuPublisher::SyncedImuPublisher(ros::Publisher imu_publisher, std::size_t waiting_list_size):
_publisher(imu_publisher), _pause_mode(false),
_waiting_list_size(waiting_list_size)
{}
SyncedImuPublisher::~SyncedImuPublisher()
{
PublishPendingMessages();
}
void SyncedImuPublisher::Publish(sensor_msgs::Imu imu_msg)
{
std::lock_guard<std::mutex> lock_guard(_mutex);
if (_pause_mode)
{
if (_pending_messages.size() >= _waiting_list_size)
{
throw std::runtime_error("SyncedImuPublisher inner list reached maximum size of " + std::to_string(_pending_messages.size()));
}
_pending_messages.push(imu_msg);
}
else
{
_publisher.publish(imu_msg);
// ROS_INFO_STREAM("iid1:" << imu_msg.header.seq << ", time: " << std::setprecision (20) << imu_msg.header.stamp.toSec());
}
return;
}
void SyncedImuPublisher::Pause()
{
if (!_is_enabled) return;
std::lock_guard<std::mutex> lock_guard(_mutex);
_pause_mode = true;
}
void SyncedImuPublisher::Resume()
{
std::lock_guard<std::mutex> lock_guard(_mutex);
PublishPendingMessages();
_pause_mode = false;
}
void SyncedImuPublisher::PublishPendingMessages()
{
// ROS_INFO_STREAM("publish imu: " << _pending_messages.size());
while (!_pending_messages.empty())
{
const sensor_msgs::Imu &imu_msg = _pending_messages.front();
_publisher.publish(imu_msg);
// ROS_INFO_STREAM("iid2:" << imu_msg.header.seq << ", time: " << std::setprecision (20) << imu_msg.header.stamp.toSec());
_pending_messages.pop();
}
}
std::string BaseRealSenseNode::getNamespaceStr()
{
auto ns = ros::this_node::getNamespace();
ns.erase(std::remove(ns.begin(), ns.end(), '/'), ns.end());
return ns;
}
BaseRealSenseNode::BaseRealSenseNode(ros::NodeHandle& nodeHandle,
ros::NodeHandle& privateNodeHandle,
rs2::device dev,
const std::string& serial_no) :
_is_running(true), _base_frame_id(""), _node_handle(nodeHandle),
_pnh(privateNodeHandle), _dev(dev), _json_file_path(""),
_serial_no(serial_no),
_is_initialized_time_base(false),
_namespace(getNamespaceStr())
{
// Types for depth stream
_format[RS2_STREAM_DEPTH] = RS2_FORMAT_Z16;
_image_format[RS2_STREAM_DEPTH] = CV_16UC1; // CVBridge type
_encoding[RS2_STREAM_DEPTH] = sensor_msgs::image_encodings::TYPE_16UC1; // ROS message type
_unit_step_size[RS2_STREAM_DEPTH] = sizeof(uint16_t); // sensor_msgs::ImagePtr row step size
_stream_name[RS2_STREAM_DEPTH] = "depth";
// Types for confidence stream
_image_format[RS2_STREAM_CONFIDENCE] = CV_8UC1; // CVBridge type
_encoding[RS2_STREAM_CONFIDENCE] = sensor_msgs::image_encodings::MONO8; // ROS message type
_unit_step_size[RS2_STREAM_CONFIDENCE] = sizeof(uint8_t); // sensor_msgs::ImagePtr row step size
_stream_name[RS2_STREAM_CONFIDENCE] = "confidence";
// Infrared stream
_format[RS2_STREAM_INFRARED] = RS2_FORMAT_Y8;
_image_format[RS2_STREAM_INFRARED] = CV_8UC1; // CVBridge type
_encoding[RS2_STREAM_INFRARED] = sensor_msgs::image_encodings::MONO8; // ROS message type
_unit_step_size[RS2_STREAM_INFRARED] = sizeof(uint8_t); // sensor_msgs::ImagePtr row step size
_stream_name[RS2_STREAM_INFRARED] = "infra";
// Types for color stream
_image_format[RS2_STREAM_COLOR] = CV_8UC3; // CVBridge type
_encoding[RS2_STREAM_COLOR] = sensor_msgs::image_encodings::RGB8; // ROS message type
_unit_step_size[RS2_STREAM_COLOR] = 3; // sensor_msgs::ImagePtr row step size
_stream_name[RS2_STREAM_COLOR] = "color";
_depth_aligned_encoding[RS2_STREAM_COLOR] = sensor_msgs::image_encodings::TYPE_16UC1;
// Types for fisheye stream
_image_format[RS2_STREAM_FISHEYE] = CV_8UC1; // CVBridge type
_encoding[RS2_STREAM_FISHEYE] = sensor_msgs::image_encodings::MONO8; // ROS message type
_unit_step_size[RS2_STREAM_FISHEYE] = sizeof(uint8_t); // sensor_msgs::ImagePtr row step size
_stream_name[RS2_STREAM_FISHEYE] = "fisheye";
// Types for Motion-Module streams
_stream_name[RS2_STREAM_GYRO] = "gyro";
_stream_name[RS2_STREAM_ACCEL] = "accel";
_stream_name[RS2_STREAM_POSE] = "pose";
_monitor_options = {RS2_OPTION_ASIC_TEMPERATURE, RS2_OPTION_PROJECTOR_TEMPERATURE};
}
BaseRealSenseNode::~BaseRealSenseNode()
{
// Kill dynamic transform thread
_is_running = false;
_cv_tf.notify_one();
if (_tf_t && _tf_t->joinable())
_tf_t->join();
if (_update_functions_t && _update_functions_t->joinable())
_update_functions_t->join();
_cv_monitoring.notify_one();
if (_monitoring_t && _monitoring_t->joinable())
{
_monitoring_t->join();
}
std::set<std::string> module_names;
for (const std::pair<stream_index_pair, std::vector<rs2::stream_profile>>& profile : _enabled_profiles)
{
try
{
std::string module_name = _sensors[profile.first].get_info(RS2_CAMERA_INFO_NAME);
std::pair< std::set<std::string>::iterator, bool> res = module_names.insert(module_name);
if (res.second)
{
_sensors[profile.first].stop();
_sensors[profile.first].close();
}
}
catch (const rs2::error& e)
{
ROS_ERROR_STREAM("Exception: " << e.what());
}
}
}
void BaseRealSenseNode::toggleSensors(bool enabled)
{
if(enabled)
{
std::map<std::string, std::vector<rs2::stream_profile> > profiles;
std::map<std::string, rs2::sensor> active_sensors;
for (const std::pair<stream_index_pair, std::vector<rs2::stream_profile>>& profile : _enabled_profiles)
{
std::string module_name = _sensors[profile.first].get_info(RS2_CAMERA_INFO_NAME);
ROS_INFO_STREAM("insert " << rs2_stream_to_string(profile.second.begin()->stream_type())
<< " to " << module_name);
profiles[module_name].insert(profiles[module_name].begin(),
profile.second.begin(),
profile.second.end());
active_sensors[module_name] = _sensors[profile.first];
}
for (const std::pair<std::string, std::vector<rs2::stream_profile> >& sensor_profile : profiles)
{
std::string module_name = sensor_profile.first;
rs2::sensor sensor = active_sensors[module_name];
sensor.open(sensor_profile.second);
sensor.start(_sensors_callback[module_name]);
if (sensor.is<rs2::depth_sensor>())
{
_depth_scale_meters = sensor.as<rs2::depth_sensor>().get_depth_scale();
}
}
}
else
{
std::set<std::string> module_names;
for (const std::pair<stream_index_pair, std::vector<rs2::stream_profile>>& profile : _enabled_profiles)
{
std::string module_name = _sensors[profile.first].get_info(RS2_CAMERA_INFO_NAME);
std::pair< std::set<std::string>::iterator, bool> res = module_names.insert(module_name);
if (res.second)
{
_sensors[profile.first].stop();
_sensors[profile.first].close();
}
}
}
}
void BaseRealSenseNode::setupErrorCallback()
{
for (auto&& s : _dev.query_sensors())
{
s.set_notifications_callback([&](const rs2::notification& n)
{
std::vector<std::string> error_strings({"RT IC2 Config error",
"Left IC2 Config error"});
if (n.get_severity() >= RS2_LOG_SEVERITY_ERROR)
{
ROS_WARN_STREAM("Hardware Notification:" << n.get_description() << "," << n.get_timestamp() << "," << n.get_severity() << "," << n.get_category());
}
if (error_strings.end() != std::find_if(error_strings.begin(), error_strings.end(), [&n] (std::string err)
{return (n.get_description().find(err) != std::string::npos); }))
{
ROS_ERROR_STREAM("Performing Hardware Reset.");
_dev.hardware_reset();
}
});
}
}
void BaseRealSenseNode::publishTopics()
{
getParameters();
setupDevice();
setupFilters();
registerHDRoptions();
registerDynamicReconfigCb(_node_handle);
setupErrorCallback();
enable_devices();
setupPublishers();
setupStreams();
SetBaseStream();
registerAutoExposureROIOptions(_node_handle);
publishStaticTransforms();
publishIntrinsics();
startMonitoring();
publishServices();
ROS_INFO_STREAM("RealSense Node Is Up!");
}
void BaseRealSenseNode::runFirstFrameInitialization(rs2_stream stream_type)
{
if (_is_first_frame[stream_type])
{
ROS_DEBUG_STREAM("runFirstFrameInitialization: " << _video_functions_stack.size() << ", " << rs2_stream_to_string(stream_type));
_is_first_frame[stream_type] = false;
if (!_video_functions_stack[stream_type].empty())
{
std::thread t = std::thread([=]()
{
while (!_video_functions_stack[stream_type].empty())
{
_video_functions_stack[stream_type].back()();
_video_functions_stack[stream_type].pop_back();
}
});
t.detach();
}
}
}
bool is_checkbox(rs2::options sensor, rs2_option option)
{
rs2::option_range op_range = sensor.get_option_range(option);
return op_range.max == 1.0f &&
op_range.min == 0.0f &&
op_range.step == 1.0f;
}
bool is_enum_option(rs2::options sensor, rs2_option option)
{
static const int MAX_ENUM_OPTION_VALUES(100);
static const float EPSILON(0.05);
rs2::option_range op_range = sensor.get_option_range(option);
if (abs((op_range.step - 1)) > EPSILON || (op_range.max > MAX_ENUM_OPTION_VALUES)) return false;
for (auto i = op_range.min; i <= op_range.max; i += op_range.step)
{
if (sensor.get_option_value_description(option, i) == nullptr)
continue;
return true;
}
return false;
}
bool is_int_option(rs2::options sensor, rs2_option option)
{
rs2::option_range op_range = sensor.get_option_range(option);
return (op_range.step == 1.0);
}
std::map<std::string, int> get_enum_method(rs2::options sensor, rs2_option option)
{
std::map<std::string, int> dict; // An enum to set size
if (is_enum_option(sensor, option))
{
rs2::option_range op_range = sensor.get_option_range(option);
const auto op_range_min = int(op_range.min);
const auto op_range_max = int(op_range.max);
const auto op_range_step = int(op_range.step);
for (auto val = op_range_min; val <= op_range_max; val += op_range_step)
{
if (sensor.get_option_value_description(option, val) == nullptr)
continue;
dict[sensor.get_option_value_description(option, val)] = val;
}
}
return dict;
}
namespace realsense2_camera
{
template <typename K, typename V>
std::ostream& operator<<(std::ostream& os, const std::map<K, V>& m)
{
os << '{';
for (const auto& kv : m)
{
os << " {" << kv.first << ": " << kv.second << '}';
}
os << " }";
return os;
}
}
/**
* Same as ros::names::isValidCharInName, but re-implemented here because it's not exposed.
*/
bool isValidCharInName(char c)
{
return std::isalnum(c) || c == '/' || c == '_';
}
/**
* ROS Graph Resource names don't allow spaces and hyphens (see http://wiki.ros.org/Names),
* so we replace them here with underscores.
*/
std::string create_graph_resource_name(const std::string &original_name)
{
std::string fixed_name = original_name;
std::transform(fixed_name.begin(), fixed_name.end(), fixed_name.begin(),
[](unsigned char c) { return std::tolower(c); });
std::replace_if(fixed_name.begin(), fixed_name.end(), [](const char c) { return !isValidCharInName(c); },
'_');
return fixed_name;
}
void BaseRealSenseNode::set_auto_exposure_roi(const std::string option_name, rs2::sensor sensor, int new_value)
{
rs2::region_of_interest& auto_exposure_roi(_auto_exposure_roi[sensor.get_info(RS2_CAMERA_INFO_NAME)]);
if (option_name == "left")
auto_exposure_roi.min_x = new_value;
else if (option_name == "right")
auto_exposure_roi.max_x = new_value;
else if (option_name == "top")
auto_exposure_roi.min_y = new_value;
else if (option_name == "bottom")
auto_exposure_roi.max_y = new_value;
else
{
ROS_WARN_STREAM("Invalid option_name: " << option_name << " while setting auto exposure ROI.");
return;
}
set_sensor_auto_exposure_roi(sensor);
}
void BaseRealSenseNode::set_sensor_auto_exposure_roi(rs2::sensor sensor)
{
const rs2::region_of_interest& auto_exposure_roi(_auto_exposure_roi[sensor.get_info(RS2_CAMERA_INFO_NAME)]);
try
{
sensor.as<rs2::roi_sensor>().set_region_of_interest(auto_exposure_roi);
}
catch(const std::runtime_error& e)
{
ROS_ERROR_STREAM(e.what());
}
}
void BaseRealSenseNode::readAndSetDynamicParam(ros::NodeHandle& nh1, std::shared_ptr<ddynamic_reconfigure::DDynamicReconfigure> ddynrec,
const std::string option_name, const int min_val, const int max_val, rs2::sensor sensor,
int* option_value)
{
nh1.param(option_name, *option_value, *option_value); //param (const std::string ¶m_name, T ¶m_val, const T &default_val) const
if (*option_value < min_val) *option_value = min_val;
if (*option_value > max_val) *option_value = max_val;
ddynrec->registerVariable<int>(
option_name, *option_value, [this, sensor, option_name](int new_value){set_auto_exposure_roi(option_name, sensor, new_value);},
"auto-exposure " + option_name + " coordinate", min_val, max_val);
}
void BaseRealSenseNode::registerAutoExposureROIOptions(ros::NodeHandle& nh)
{
for (const std::pair<stream_index_pair, std::vector<rs2::stream_profile>>& profile : _enabled_profiles)
{
rs2::sensor sensor = _sensors[profile.first];
std::string module_base_name(sensor.get_info(RS2_CAMERA_INFO_NAME));
if (sensor.is<rs2::roi_sensor>() && _auto_exposure_roi.find(module_base_name) == _auto_exposure_roi.end())
{
int max_x(_width[profile.first]-1);
int max_y(_height[profile.first]-1);
std::string module_name = create_graph_resource_name(module_base_name) +"/auto_exposure_roi";
ros::NodeHandle nh1(nh, module_name);
std::shared_ptr<ddynamic_reconfigure::DDynamicReconfigure> ddynrec = std::make_shared<ddynamic_reconfigure::DDynamicReconfigure>(nh1);
_auto_exposure_roi[module_base_name] = {0, 0, max_x, max_y};
rs2::region_of_interest& auto_exposure_roi(_auto_exposure_roi[module_base_name]);
readAndSetDynamicParam(nh1, ddynrec, "left", 0, max_x, sensor, &(auto_exposure_roi.min_x));
readAndSetDynamicParam(nh1, ddynrec, "right", 0, max_x, sensor, &(auto_exposure_roi.max_x));
readAndSetDynamicParam(nh1, ddynrec, "top", 0, max_y, sensor, &(auto_exposure_roi.min_y));
readAndSetDynamicParam(nh1, ddynrec, "bottom", 0, max_y, sensor, &(auto_exposure_roi.max_y));
ddynrec->publishServicesTopics();
_ddynrec.push_back(ddynrec);
// Initiate the call to set_sensor_auto_exposure_roi, after the first frame arrive.
rs2_stream stream_type = profile.first.first;
_video_functions_stack[stream_type].push_back([this, sensor](){set_sensor_auto_exposure_roi(sensor);});
_is_first_frame[stream_type] = true;
}
}
}
void BaseRealSenseNode::registerDynamicOption(ros::NodeHandle& nh, rs2::options sensor, std::string& module_name)
{
ros::NodeHandle nh1(nh, module_name);
std::shared_ptr<ddynamic_reconfigure::DDynamicReconfigure> ddynrec = std::make_shared<ddynamic_reconfigure::DDynamicReconfigure>(nh1);
for (auto i = 0; i < RS2_OPTION_COUNT; i++)
{
rs2_option option = static_cast<rs2_option>(i);
const std::string option_name(create_graph_resource_name(rs2_option_to_string(option)));
try
{
if (!sensor.supports(option) || sensor.is_option_read_only(option))
{
continue;
}
if (is_checkbox(sensor, option))
{
auto option_value = bool(sensor.get_option(option));
if (nh1.param(option_name, option_value, option_value))
{
sensor.set_option(option, option_value);
}
ddynrec->registerVariable<bool>(
option_name, option_value,
[option, sensor](bool new_value) { sensor.set_option(option, new_value); },
sensor.get_option_description(option));
continue;
}
const auto enum_dict = get_enum_method(sensor, option);
if (enum_dict.empty())
{
rs2::option_range op_range = sensor.get_option_range(option);
const auto sensor_option_value = sensor.get_option(option);
auto option_value = sensor_option_value;
if (nh1.param(option_name, option_value, option_value))
{
if (option_value < op_range.min || op_range.max < option_value)
{
ROS_WARN_STREAM("Param '" << nh1.resolveName(option_name) << "' has value " << option_value
<< " outside the range [" << op_range.min << ", " << op_range.max
<< "]. Using current sensor value " << sensor_option_value << " instead.");
option_value = sensor_option_value;
}
else
{
sensor.set_option(option, option_value);
}
}
if (option_value < op_range.min || op_range.max < option_value)
{
ROS_WARN_STREAM("Param '" << nh1.resolveName(option_name) << "' has value " << option_value
<< " that is not in range [" << op_range.min << ", " << op_range.max << "]"
<< ". Removing this parameter from dynamic reconfigure options.");
continue;
}
if (is_int_option(sensor, option))
{
ddynrec->registerVariable<int>(
option_name, int(option_value),
[option, sensor](int new_value) { sensor.set_option(option, new_value); },
sensor.get_option_description(option), int(op_range.min), int(op_range.max));
}
else
{
if (i == RS2_OPTION_DEPTH_UNITS)
{
if (ROS_DEPTH_SCALE >= op_range.min && ROS_DEPTH_SCALE <= op_range.max)
{
sensor.set_option(option, ROS_DEPTH_SCALE);
op_range.min = ROS_DEPTH_SCALE;
op_range.max = ROS_DEPTH_SCALE;
_depth_scale_meters = ROS_DEPTH_SCALE;
}
}
else
{
ddynrec->registerVariable<double>(
option_name, option_value,
[option, sensor](double new_value) { sensor.set_option(option, new_value); },
sensor.get_option_description(option), double(op_range.min), double(op_range.max));
}
}
}
else
{
const auto sensor_option_value = sensor.get_option(option);
auto option_value = int(sensor_option_value);
if (nh1.param(option_name, option_value, option_value))
{
if (std::find_if(enum_dict.cbegin(), enum_dict.cend(),
[&option_value](const std::pair<std::string, int>& kv) {
return kv.second == option_value;
}) == enum_dict.cend())
{
ROS_WARN_STREAM("Param '" << nh1.resolveName(option_name) << "' has value " << option_value
<< " that is not in the enum " << enum_dict
<< ". Using current sensor value " << sensor_option_value << " instead.");
option_value = sensor_option_value;
}
else
{
sensor.set_option(option, option_value);
}
}
if (std::find_if(enum_dict.cbegin(), enum_dict.cend(),
[&option_value](const std::pair<std::string, int>& kv) {
return kv.second == option_value;
}) == enum_dict.cend())
{
ROS_WARN_STREAM("Param '" << nh1.resolveName(option_name) << "' has value " << option_value
<< " that is not in the enum " << enum_dict
<< ". Removing this parameter from dynamic reconfigure options.");
continue;
}
if (module_name == "stereo_module" && i == RS2_OPTION_SEQUENCE_ID)
{
ddynrec->registerEnumVariable<int>(
option_name, option_value,
[this, option, sensor, module_name](int new_value)
{
sensor.set_option(option, new_value);
_update_functions_v.push_back([this, module_name, sensor]()
{set_sensor_parameter_to_ros(module_name, sensor, RS2_OPTION_EXPOSURE);});
_update_functions_v.push_back([this, module_name, sensor]()
{set_sensor_parameter_to_ros(module_name, sensor, RS2_OPTION_GAIN);});
_update_functions_cv.notify_one();
},
sensor.get_option_description(option), enum_dict);
}
else
{
ddynrec->registerEnumVariable<int>(
option_name, option_value,
[option, sensor](int new_value) { sensor.set_option(option, new_value); },
sensor.get_option_description(option), enum_dict);
}
}
}
catch(const rs2::backend_error& e)
{
ROS_WARN_STREAM("Failed to set option: " << option_name << ": " << e.what());
}
catch(const std::exception& e)
{
std::cerr << e.what() << '\n';
}
}
ddynrec->publishServicesTopics();
_ddynrec.push_back(ddynrec);
}
void BaseRealSenseNode::registerDynamicReconfigCb(ros::NodeHandle& nh)
{
ROS_INFO("Setting Dynamic reconfig parameters.");
for(rs2::sensor sensor : _dev_sensors)
{
std::string module_name = create_graph_resource_name(sensor.get_info(RS2_CAMERA_INFO_NAME));
ROS_DEBUG_STREAM("module_name:" << module_name);
registerDynamicOption(nh, sensor, module_name);
}
for (NamedFilter nfilter : _filters)
{
std::string module_name = nfilter._name;
auto sensor = *(nfilter._filter);
ROS_DEBUG_STREAM("module_name:" << module_name);
registerDynamicOption(nh, sensor, module_name);
}
ROS_INFO("Done Setting Dynamic reconfig parameters.");
}
void BaseRealSenseNode::registerHDRoptions()
{
if (std::find_if(std::begin(_filters), std::end(_filters), [](NamedFilter f){return f._name == "hdr_merge";}) == std::end(_filters))
return;
std::string module_name;
std::vector<rs2_option> options{RS2_OPTION_EXPOSURE, RS2_OPTION_GAIN};
for(rs2::sensor sensor : _dev_sensors)
{
if (!sensor.is<rs2::depth_sensor>()) continue;
std::string module_name = create_graph_resource_name(sensor.get_info(RS2_CAMERA_INFO_NAME));
// Read initialization parameters and initialize hdr_merge filter:
unsigned int seq_size = sensor.get_option(RS2_OPTION_SEQUENCE_SIZE);
for (unsigned int seq_id = 1; seq_id <= seq_size; seq_id++ )
{
sensor.set_option(RS2_OPTION_SEQUENCE_ID, seq_id);
for (rs2_option& option : options)
{
std::stringstream param_name_str;
param_name_str << module_name << "/" << create_graph_resource_name(rs2_option_to_string(option)) << "/" << seq_id;
std::string param_name(param_name_str.str());
ROS_INFO_STREAM("Reading option: " << param_name);
int option_value = sensor.get_option(option);
int user_set_option_value;
_pnh.param(param_name, user_set_option_value, option_value);
_pnh.deleteParam(param_name);
if (option_value != user_set_option_value)
{
ROS_INFO_STREAM("Set " << rs2_option_to_string(option) << " to " << user_set_option_value);
sensor.set_option(option, user_set_option_value);
}
}
}
sensor.set_option(RS2_OPTION_SEQUENCE_ID, 0); // Set back to default.
sensor.set_option(RS2_OPTION_HDR_ENABLED, true);
monitor_update_functions(); // Start parameters update thread
break;
}
}
void BaseRealSenseNode::set_sensor_parameter_to_ros(const std::string& module_name, rs2::options sensor, rs2_option option)
{
dynamic_reconfigure::ReconfigureRequest srv_req;
dynamic_reconfigure::ReconfigureResponse srv_resp;
dynamic_reconfigure::IntParameter int_param;
dynamic_reconfigure::Config conf;
int_param.name = create_graph_resource_name(rs2_option_to_string(option)); //"sequence_id"
int_param.value = sensor.get_option(option);
conf.ints.push_back(int_param);
srv_req.config = conf;
std::string service_name = module_name + "/set_parameters";
if (ros::service::call(service_name, srv_req, srv_resp)) {
ROS_INFO_STREAM( "call to set " << service_name << "/" << int_param.name << " to " << int_param.value << " succeeded");
} else {
ROS_ERROR_STREAM( "call to set " << service_name << "/" << int_param.name << " to " << int_param.value << " failed");
}
}
void BaseRealSenseNode::monitor_update_functions()
{
int time_interval(1000);
std::function<void()> func = [this, time_interval](){
std::mutex mu;
std::unique_lock<std::mutex> lock(mu);
while(_is_running) {
_update_functions_cv.wait_for(lock, std::chrono::milliseconds(time_interval), [&]{return !_is_running || !_update_functions_v.empty();});
while (!_update_functions_v.empty())
{
_update_functions_v.back()();
_update_functions_v.pop_back();
}
}
};
_update_functions_t = std::make_shared<std::thread>(func);
}
rs2_stream BaseRealSenseNode::rs2_string_to_stream(std::string str)
{
if (str == "RS2_STREAM_ANY")
return RS2_STREAM_ANY;
if (str == "RS2_STREAM_COLOR")
return RS2_STREAM_COLOR;
if (str == "RS2_STREAM_INFRARED")
return RS2_STREAM_INFRARED;
if (str == "RS2_STREAM_FISHEYE")
return RS2_STREAM_FISHEYE;
throw std::runtime_error("Unknown stream string " + str);
}
void BaseRealSenseNode::getParameters()
{
ROS_INFO("getParameters...");
// Setup system to use RGB image from the infra stream if configured by user
bool infra_rgb;
_pnh.param("infra_rgb", infra_rgb, false);
if (infra_rgb)
{
_format[RS2_STREAM_INFRARED] = RS2_FORMAT_RGB8;
_image_format[RS2_STREAM_INFRARED] = CV_8UC3; // CVBridge type
_encoding[RS2_STREAM_INFRARED] = sensor_msgs::image_encodings::RGB8; // ROS message type
_unit_step_size[RS2_STREAM_INFRARED] = 3 * sizeof(uint8_t); // sensor_msgs::ImagePtr row step size
ROS_INFO_STREAM("Infrared RGB stream enabled");
}
_pnh.param("align_depth", _align_depth, ALIGN_DEPTH);
_pnh.param("enable_pointcloud", _pointcloud, POINTCLOUD);
std::string pc_texture_stream("");
int pc_texture_idx;
_pnh.param("pointcloud_texture_stream", pc_texture_stream, std::string("RS2_STREAM_COLOR"));
_pnh.param("pointcloud_texture_index", pc_texture_idx, 0);
_pointcloud_texture = stream_index_pair{rs2_string_to_stream(pc_texture_stream), pc_texture_idx};
_pnh.param("filters", _filters_str, DEFAULT_FILTERS);
_pointcloud |= (_filters_str.find("pointcloud") != std::string::npos);
_pnh.param("publish_tf", _publish_tf, PUBLISH_TF);
_pnh.param("tf_publish_rate", _tf_publish_rate, TF_PUBLISH_RATE);
_pnh.param("enable_sync", _sync_frames, SYNC_FRAMES);
if (_pointcloud || _align_depth || _filters_str.size() > 0)
_sync_frames = true;
_pnh.param("json_file_path", _json_file_path, std::string(""));
for (auto& stream : IMAGE_STREAMS)
{
std::string param_name(_stream_name[stream.first] + "_width");
_pnh.param(param_name, _width[stream], IMAGE_WIDTH);
ROS_DEBUG_STREAM("parameter:" << param_name << " = " << _width[stream]);
param_name = _stream_name[stream.first] + "_height";
_pnh.param(param_name, _height[stream], IMAGE_HEIGHT);
ROS_DEBUG_STREAM("parameter:" << param_name << " = " << _height[stream]);
param_name = _stream_name[stream.first] + "_fps";
_pnh.param(param_name, _fps[stream], IMAGE_FPS);
ROS_DEBUG_STREAM("parameter:" << param_name << " = " << _fps[stream]);
param_name = "enable_" + STREAM_NAME(stream);
_pnh.param(param_name, _enable[stream], true);
ROS_DEBUG_STREAM("parameter:" << param_name << " = " << _enable[stream]);
}
for (auto& stream : HID_STREAMS)
{
std::string param_name(_stream_name[stream.first] + "_fps");
ROS_DEBUG_STREAM("reading parameter:" << param_name);
_pnh.param(param_name, _fps[stream], IMU_FPS);
param_name = "enable_" + STREAM_NAME(stream);
_pnh.param(param_name, _enable[stream], ENABLE_IMU);
ROS_DEBUG_STREAM("_enable[" << _stream_name[stream.first] << "]:" << _enable[stream]);
}
_pnh.param("base_frame_id", _base_frame_id, DEFAULT_BASE_FRAME_ID);
_pnh.param("odom_frame_id", _odom_frame_id, DEFAULT_ODOM_FRAME_ID);
std::vector<stream_index_pair> streams(IMAGE_STREAMS);
streams.insert(streams.end(), HID_STREAMS.begin(), HID_STREAMS.end());
for (auto& stream : streams)
{
std::string param_name(static_cast<std::ostringstream&&>(std::ostringstream() << STREAM_NAME(stream) << "_frame_id").str());
_pnh.param(param_name, _frame_id[stream], FRAME_ID(stream));
ROS_DEBUG_STREAM("frame_id: reading parameter:" << param_name << " : " << _frame_id[stream]);
param_name = static_cast<std::ostringstream&&>(std::ostringstream() << STREAM_NAME(stream) << "_optical_frame_id").str();
_pnh.param(param_name, _optical_frame_id[stream], OPTICAL_FRAME_ID(stream));
ROS_DEBUG_STREAM("optical: reading parameter:" << param_name << " : " << _optical_frame_id[stream]);
}
std::string unite_imu_method_str("");
_pnh.param("unite_imu_method", unite_imu_method_str, DEFAULT_UNITE_IMU_METHOD);
if (unite_imu_method_str == "linear_interpolation")
_imu_sync_method = imu_sync_method::LINEAR_INTERPOLATION;
else if (unite_imu_method_str == "copy")
_imu_sync_method = imu_sync_method::COPY;
else
_imu_sync_method = imu_sync_method::NONE;
if (_imu_sync_method > imu_sync_method::NONE)
{
_pnh.param("imu_optical_frame_id", _optical_frame_id[GYRO], DEFAULT_IMU_OPTICAL_FRAME_ID);
}
{
stream_index_pair stream(COLOR);
std::string param_name(static_cast<std::ostringstream&&>(std::ostringstream() << "aligned_depth_to_" << STREAM_NAME(stream) << "_frame_id").str());
_pnh.param(param_name, _depth_aligned_frame_id[stream], ALIGNED_DEPTH_TO_FRAME_ID(stream));
}
_pnh.param("allow_no_texture_points", _allow_no_texture_points, ALLOW_NO_TEXTURE_POINTS);
_pnh.param("ordered_pc", _ordered_pc, ORDERED_POINTCLOUD);
_pnh.param("clip_distance", _clipping_distance, static_cast<float>(-1.0));
_pnh.param("linear_accel_cov", _linear_accel_cov, static_cast<double>(0.01));
_pnh.param("angular_velocity_cov", _angular_velocity_cov, static_cast<double>(0.01));
_pnh.param("hold_back_imu_for_frames", _hold_back_imu_for_frames, HOLD_BACK_IMU_FOR_FRAMES);
_pnh.param("publish_odom_tf", _publish_odom_tf, PUBLISH_ODOM_TF);
}
void BaseRealSenseNode::setupDevice()
{
ROS_INFO("setupDevice...");
try{
if (!_json_file_path.empty())
{
if (_dev.is<rs2::serializable_device>())
{
std::stringstream ss;
std::ifstream in(_json_file_path);
if (in.is_open())
{
ss << in.rdbuf();
std::string json_file_content = ss.str();
auto adv = _dev.as<rs2::serializable_device>();
adv.load_json(json_file_content);
ROS_INFO_STREAM("JSON file is loaded! (" << _json_file_path << ")");
}
else
ROS_WARN_STREAM("JSON file provided doesn't exist! (" << _json_file_path << ")");
}
else
ROS_WARN("Device does not support advanced settings!");
}
else
ROS_INFO("JSON file is not provided");
ROS_INFO_STREAM("ROS Node Namespace: " << _namespace);
auto camera_name = _dev.get_info(RS2_CAMERA_INFO_NAME);
ROS_INFO_STREAM("Device Name: " << camera_name);
ROS_INFO_STREAM("Device Serial No: " << _serial_no);
auto camera_id = _dev.get_info(RS2_CAMERA_INFO_PHYSICAL_PORT);
ROS_INFO_STREAM("Device physical port: " << camera_id);
auto fw_ver = _dev.get_info(RS2_CAMERA_INFO_FIRMWARE_VERSION);
ROS_INFO_STREAM("Device FW version: " << fw_ver);
auto pid = _dev.get_info(RS2_CAMERA_INFO_PRODUCT_ID);
ROS_INFO_STREAM("Device Product ID: 0x" << pid);
ROS_INFO_STREAM("Enable PointCloud: " << ((_pointcloud)?"On":"Off"));
ROS_INFO_STREAM("Align Depth: " << ((_align_depth)?"On":"Off"));
ROS_INFO_STREAM("Sync Mode: " << ((_sync_frames)?"On":"Off"));
_dev_sensors = _dev.query_sensors();
std::function<void(rs2::frame)> frame_callback_function, imu_callback_function;
if (_sync_frames)
{
frame_callback_function = _syncer;
auto frame_callback_inner = [this](rs2::frame frame){
frame_callback(frame);
};
_syncer.start(frame_callback_inner);
}
else
{
frame_callback_function = [this](rs2::frame frame){frame_callback(frame);};
}
if (_imu_sync_method == imu_sync_method::NONE)
{
imu_callback_function = [this](rs2::frame frame){imu_callback(frame);};
}
else
{
imu_callback_function = [this](rs2::frame frame){imu_callback_sync(frame, _imu_sync_method);};
}
std::function<void(rs2::frame)> multiple_message_callback_function = [this](rs2::frame frame){multiple_message_callback(frame, _imu_sync_method);};
ROS_INFO_STREAM("Device Sensors: ");
for(auto&& sensor : _dev_sensors)
{
for (auto& profile : sensor.get_stream_profiles())
{
auto video_profile = profile.as<rs2::video_stream_profile>();
stream_index_pair sip(video_profile.stream_type(), video_profile.stream_index());
if (_sensors.find( sip ) != _sensors.end())
continue;
_sensors[sip] = sensor;
}
std::string module_name = sensor.get_info(RS2_CAMERA_INFO_NAME);
if (sensor.is<rs2::depth_sensor>())
{
_sensors_callback[module_name] = frame_callback_function;
}
else if (sensor.is<rs2::color_sensor>())
{
_sensors_callback[module_name] = frame_callback_function;
}
else if (sensor.is<rs2::fisheye_sensor>())
{
_sensors_callback[module_name] = frame_callback_function;
}
else if (sensor.is<rs2::motion_sensor>())
{
_sensors_callback[module_name] = imu_callback_function;
}
else if (sensor.is<rs2::pose_sensor>())
{
_sensors_callback[module_name] = multiple_message_callback_function;
}
else
{
ROS_ERROR_STREAM("Module Name \"" << module_name << "\" isn't supported by LibRealSense! Terminating RealSense Node...");
ros::shutdown();
exit(1);
}
ROS_INFO_STREAM(module_name << " was found.");
}
// Update "enable" map
for (std::pair<stream_index_pair, bool> const& enable : _enable )
{
const stream_index_pair& stream_index(enable.first);
if (enable.second && _sensors.find(stream_index) == _sensors.end())
{
ROS_INFO_STREAM("(" << rs2_stream_to_string(stream_index.first) << ", " << stream_index.second << ") sensor isn't supported by current device! -- Skipping...");
_enable[enable.first] = false;
}
}
}
catch(const std::exception& ex)
{
ROS_ERROR_STREAM("An exception has been thrown: " << ex.what());
throw;
}
catch(...)
{
ROS_ERROR_STREAM("Unknown exception has occured!");
throw;
}
}
void BaseRealSenseNode::setupPublishers()
{
ROS_INFO("setupPublishers...");
image_transport::ImageTransport image_transport(_node_handle);
for (auto& stream : IMAGE_STREAMS)
{
if (_enable[stream])
{
std::stringstream image_raw, camera_info, topic_metadata;
bool rectified_image = false;
if (stream == DEPTH || stream == CONFIDENCE || stream == INFRA1 || stream == INFRA2)
rectified_image = true;
std::string stream_name(STREAM_NAME(stream));
image_raw << stream_name << "/image_" << ((rectified_image)?"rect_":"") << "raw";
camera_info << stream_name << "/camera_info";
topic_metadata << stream_name << "/metadata";
std::shared_ptr<FrequencyDiagnostics> frequency_diagnostics(new FrequencyDiagnostics(_fps[stream], stream_name, _serial_no));
_image_publishers[stream] = {image_transport.advertise(image_raw.str(), 1), frequency_diagnostics};
_info_publisher[stream] = _node_handle.advertise<sensor_msgs::CameraInfo>(camera_info.str(), 1);
_metadata_publishers[stream] = std::make_shared<ros::Publisher>(_node_handle.advertise<realsense2_camera::Metadata>(topic_metadata.str(), 1));
if (_align_depth && stream == COLOR)
{
std::stringstream aligned_image_raw, aligned_camera_info;
aligned_image_raw << "aligned_depth_to_" << stream_name << "/image_raw";
aligned_camera_info << "aligned_depth_to_" << stream_name << "/camera_info";
std::string aligned_stream_name = "aligned_depth_to_" + stream_name;
std::shared_ptr<FrequencyDiagnostics> frequency_diagnostics(new FrequencyDiagnostics(_fps[stream], aligned_stream_name, _serial_no));
_depth_aligned_image_publishers[stream] = {image_transport.advertise(aligned_image_raw.str(), 1), frequency_diagnostics};
_depth_aligned_info_publisher[stream] = _node_handle.advertise<sensor_msgs::CameraInfo>(aligned_camera_info.str(), 1);
}
if (stream == DEPTH && _pointcloud)
{
_pointcloud_publisher = _node_handle.advertise<sensor_msgs::PointCloud2>("depth/color/points", 1);