forked from IntelRealSense/realsense-ros
-
Notifications
You must be signed in to change notification settings - Fork 2
/
Copy pathbase_nodelet.cpp
1228 lines (1085 loc) · 40.1 KB
/
base_nodelet.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/******************************************************************************
Copyright (c) 2016, Intel Corporation
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
1. Redistributions of source code must retain the above copyright notice, this
list of conditions and the following disclaimer.
2. 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.
3. Neither the name of the copyright holder 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 HOLDER 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 <realsense_camera/base_nodelet.h>
using namespace cv;
using namespace std;
PLUGINLIB_EXPORT_CLASS (realsense_camera::BaseNodelet, nodelet::Nodelet)
namespace realsense_camera
{
/*
* Nodelet Destructor.
*/
BaseNodelet::~BaseNodelet()
{
if (enable_tf_ == true && enable_tf_dynamic_ == true)
{
transform_thread_->join();
}
stopCamera();
if (rs_context_)
{
rs_delete_context(rs_context_, &rs_error_);
rs_context_ = NULL;
checkError();
}
// Kill all old system progress groups
while (! system_proc_groups_.empty())
{
killpg(system_proc_groups_.front(), SIGHUP);
system_proc_groups_.pop();
}
ROS_INFO_STREAM(nodelet_name_ << " - Stopping...");
if (! ros::isShuttingDown())
{
ros::shutdown();
}
}
/*
* Initialize the nodelet.
*/
void BaseNodelet::onInit() try
{
getParameters();
if (enable_[RS_STREAM_DEPTH] == false && enable_[RS_STREAM_COLOR] == false)
{
ROS_ERROR_STREAM(nodelet_name_ << " - None of the streams are enabled. Exiting!");
ros::shutdown();
}
while (false == connectToCamera()) // Poll for camera and connect if found
{
ROS_INFO_STREAM(nodelet_name_ << " - Sleeping 5 seconds then retrying to connect");
ros::Duration(5).sleep();
}
advertiseTopics();
advertiseServices();
std::vector<std::string> dynamic_params = setDynamicReconfServer();
getCameraOptions();
setStaticCameraOptions(dynamic_params);
setStreams();
startCamera();
// Start transforms thread
if (enable_tf_ == true)
{
getCameraExtrinsics();
if (enable_tf_dynamic_ == true)
{
transform_thread_ =
boost::shared_ptr<boost::thread>(new boost::thread (boost::bind(&BaseNodelet::prepareTransforms, this)));
}
else
{
publishStaticTransforms();
}
}
// Start dynamic reconfigure callback
startDynamicReconfCallback();
}
catch(const rs::error & e)
{
ROS_ERROR_STREAM(nodelet_name_ << " - " << "RealSense error calling "
<< e.get_failed_function() << "(" << e.get_failed_args() << "):\n "
<< e.what());
ros::shutdown();
}
catch(const std::exception & e)
{
ROS_ERROR_STREAM(nodelet_name_ << " - " << e.what());
ros::shutdown();
}
catch(...)
{
ROS_ERROR_STREAM(nodelet_name_ << " - Caught unknown expection...shutting down!");
ros::shutdown();
}
/*
* Get the nodelet parameters.
*/
void BaseNodelet::getParameters()
{
nodelet_name_ = getName();
nh_ = getNodeHandle();
pnh_ = getPrivateNodeHandle();
pnh_.getParam("serial_no", serial_no_);
pnh_.getParam("usb_port_id", usb_port_id_);
pnh_.getParam("camera_type", camera_type_);
pnh_.param("mode", mode_, DEFAULT_MODE);
pnh_.param("enable_depth", enable_[RS_STREAM_DEPTH], ENABLE_DEPTH);
pnh_.param("enable_color", enable_[RS_STREAM_COLOR], ENABLE_COLOR);
pnh_.param("enable_ir", enable_[RS_STREAM_INFRARED], ENABLE_IR);
pnh_.param("enable_pointcloud", enable_pointcloud_, ENABLE_PC);
pnh_.param("enable_tf", enable_tf_, ENABLE_TF);
pnh_.param("enable_tf_dynamic", enable_tf_dynamic_, ENABLE_TF_DYNAMIC);
pnh_.param("depth_width", width_[RS_STREAM_DEPTH], DEPTH_WIDTH);
pnh_.param("depth_height", height_[RS_STREAM_DEPTH], DEPTH_HEIGHT);
pnh_.param("color_width", width_[RS_STREAM_COLOR], COLOR_WIDTH);
pnh_.param("color_height", height_[RS_STREAM_COLOR], COLOR_HEIGHT);
pnh_.param("depth_fps", fps_[RS_STREAM_DEPTH], DEPTH_FPS);
pnh_.param("color_fps", fps_[RS_STREAM_COLOR], COLOR_FPS);
pnh_.param("base_frame_id", base_frame_id_, DEFAULT_BASE_FRAME_ID);
pnh_.param("depth_frame_id", frame_id_[RS_STREAM_DEPTH], DEFAULT_DEPTH_FRAME_ID);
pnh_.param("color_frame_id", frame_id_[RS_STREAM_COLOR], DEFAULT_COLOR_FRAME_ID);
pnh_.param("ir_frame_id", frame_id_[RS_STREAM_INFRARED], DEFAULT_IR_FRAME_ID);
pnh_.param("depth_optical_frame_id", optical_frame_id_[RS_STREAM_DEPTH], DEFAULT_DEPTH_OPTICAL_FRAME_ID);
pnh_.param("color_optical_frame_id", optical_frame_id_[RS_STREAM_COLOR], DEFAULT_COLOR_OPTICAL_FRAME_ID);
pnh_.param("ir_optical_frame_id", optical_frame_id_[RS_STREAM_INFRARED], DEFAULT_IR_OPTICAL_FRAME_ID);
// set IR stream to match depth
width_[RS_STREAM_INFRARED] = width_[RS_STREAM_DEPTH];
height_[RS_STREAM_INFRARED] = height_[RS_STREAM_DEPTH];
fps_[RS_STREAM_INFRARED] = fps_[RS_STREAM_DEPTH];
}
/*
* Connect to camera.
*/
bool BaseNodelet::connectToCamera()
{
rs_context_ = rs_create_context(RS_API_VERSION, &rs_error_);
if (rs_error_)
{
ROS_ERROR_STREAM(nodelet_name_ << " - No cameras detected!");
}
checkError();
int num_of_cameras = rs_get_device_count(rs_context_, &rs_error_);
checkError();
// Exit with error if no cameras are connected.
if (num_of_cameras < 1)
{
ROS_ERROR_STREAM(nodelet_name_ << " - No cameras detected!");
rs_delete_context(rs_context_, &rs_error_);
rs_context_ = NULL;
checkError();
return false;
}
// Print list of all cameras found
std::vector<int> camera_type_index = listCameras(num_of_cameras);
// Exit with error if no cameras of correct type are connected.
if (camera_type_index.size() < 1)
{
ROS_ERROR_STREAM(nodelet_name_ << " - No '" << camera_type_ << "' cameras detected!");
rs_delete_context(rs_context_, &rs_error_);
rs_context_ = NULL;
checkError();
return false;
}
// Exit with error if no serial_no or usb_port_id is specified and multiple cameras are detected.
if (serial_no_.empty() && usb_port_id_.empty() && camera_type_index.size() > 1)
{
ROS_ERROR_STREAM(nodelet_name_ <<
" - Multiple cameras of same type detected but no input serial_no or usb_port_id specified");
rs_delete_context(rs_context_, &rs_error_);
rs_context_ = NULL;
checkError();
return false;
}
// init rs_device_ before starting loop
rs_device_ = nullptr;
// find camera
for (int i: camera_type_index)
{
rs_device* rs_detected_device = rs_get_device(rs_context_, i, &rs_error_);
checkError();
// check serial_no and usb_port_id
if ((serial_no_.empty() || serial_no_ == rs_get_device_serial(rs_detected_device, &rs_error_)) &&
(usb_port_id_.empty() || usb_port_id_ == rs_get_device_usb_port_id(rs_detected_device, &rs_error_)))
{
// device found
rs_device_= rs_detected_device;
break;
}
// continue loop
}
if (rs_device_ == nullptr)
{
// camera not found
string error_msg = " - Couldn't find camera to connect with ";
error_msg += "serial_no = " + serial_no_ + ", ";
error_msg += "usb_port_id = " + usb_port_id_;
ROS_ERROR_STREAM(nodelet_name_ << error_msg);
rs_delete_context(rs_context_, &rs_error_);
rs_context_ = NULL;
checkError();
return false;
}
// print device info
ROS_INFO_STREAM(nodelet_name_ << " - Connecting to camera with Serial No: " <<
rs_get_device_serial(rs_device_, &rs_error_) <<
", USB Port ID: " << rs_get_device_usb_port_id(rs_device_, &rs_error_));
checkError();
return true;
}
/*
* List details of the detected cameras.
*/
std::vector<int> BaseNodelet::listCameras(int num_of_cameras)
{
// print list of detected cameras
std::vector<int> camera_type_index;
std::string detected_camera_msg = " - Detected the following cameras:";
for (int i = 0; i < num_of_cameras; i++)
{
// get device
rs_device* rs_detected_device = rs_get_device(rs_context_, i, &rs_error_);
// get camera name
std::string camera_name = rs_get_device_name(rs_detected_device, &rs_error_);
checkError();
if (camera_name.find(camera_type_) != std::string::npos)
{
camera_type_index.push_back(i);
}
// print camera details
detected_camera_msg = detected_camera_msg +
"\n\t\t\t\t- Serial No: " + rs_get_device_serial(rs_detected_device, &rs_error_) +
", USB Port ID: " + rs_get_device_usb_port_id(rs_detected_device, &rs_error_) +
", Name: " + camera_name +
", Camera FW: " + rs_get_device_firmware_version(rs_detected_device, &rs_error_);
checkError();
if (rs_supports(rs_detected_device, RS_CAPABILITIES_ADAPTER_BOARD, &rs_error_))
{
const char * adapter_fw = rs_get_device_info(rs_detected_device, RS_CAMERA_INFO_ADAPTER_BOARD_FIRMWARE_VERSION,
&rs_error_);
checkError();
detected_camera_msg = detected_camera_msg + ", Adapter FW: " + adapter_fw;
}
if (rs_supports(rs_detected_device, RS_CAPABILITIES_MOTION_EVENTS, &rs_error_))
{
const char * motion_module_fw = rs_get_device_info(rs_detected_device, RS_CAMERA_INFO_MOTION_MODULE_FIRMWARE_VERSION,
&rs_error_);
checkError();
detected_camera_msg = detected_camera_msg + ", Motion Module FW: " + motion_module_fw;
}
}
ROS_INFO_STREAM(nodelet_name_ + detected_camera_msg);
return camera_type_index;
}
/*
* Advertise topics.
*/
void BaseNodelet::advertiseTopics()
{
ros::NodeHandle color_nh(nh_, COLOR_NAMESPACE);
image_transport::ImageTransport color_image_transport(color_nh);
camera_publisher_[RS_STREAM_COLOR] = color_image_transport.advertiseCamera(COLOR_TOPIC, 1);
ros::NodeHandle depth_nh(nh_, DEPTH_NAMESPACE);
image_transport::ImageTransport depth_image_transport(depth_nh);
camera_publisher_[RS_STREAM_DEPTH] = depth_image_transport.advertiseCamera(DEPTH_TOPIC, 1);
pointcloud_publisher_ = depth_nh.advertise<sensor_msgs::PointCloud2>(PC_TOPIC, 1);
ros::NodeHandle ir_nh(nh_, IR_NAMESPACE);
image_transport::ImageTransport ir_image_transport(ir_nh);
camera_publisher_[RS_STREAM_INFRARED] = ir_image_transport.advertiseCamera(IR_TOPIC, 1);
}
/*
* Advertise services.
*/
void BaseNodelet::advertiseServices()
{
get_options_service_ = pnh_.advertiseService(SETTINGS_SERVICE, &BaseNodelet::getCameraOptionValues, this);
set_power_service_ = pnh_.advertiseService(CAMERA_SET_POWER_SERVICE, &BaseNodelet::setPowerCameraService, this);
force_power_service_ = pnh_.advertiseService(CAMERA_FORCE_POWER_SERVICE, &BaseNodelet::forcePowerCameraService, this);
is_powered_service_ = pnh_.advertiseService(CAMERA_IS_POWERED_SERVICE, &BaseNodelet::isPoweredCameraService, this);
}
/*
* Get the latest values of the camera options.
*/
bool BaseNodelet::getCameraOptionValues(realsense_camera::CameraConfiguration::Request & req,
realsense_camera::CameraConfiguration::Response & res)
{
std::string get_options_result_str;
std::string opt_name, opt_value;
for (CameraOptions o: camera_options_)
{
opt_name = rs_option_to_string(o.opt);
std::transform(opt_name.begin(), opt_name.end(), opt_name.begin(), ::tolower);
o.value = rs_get_device_option(rs_device_, o.opt, 0);
opt_value = boost::lexical_cast<std::string>(o.value);
get_options_result_str += opt_name + ":" + opt_value + ";";
}
res.configuration_str = get_options_result_str;
return true;
}
/*
* Check for Nodelet subscribers
*/
bool BaseNodelet::checkForSubscriber()
{
for (int index=0; index < STREAM_COUNT; index++)
{
if (camera_publisher_[index].getNumSubscribers() > 0)
{
return true;
}
}
if (pointcloud_publisher_.getNumSubscribers() > 0)
{
return true;
}
return false;
}
/*
* Service to check if camera is powered on or not
*/
bool BaseNodelet::isPoweredCameraService(realsense_camera::IsPowered::Request & req,
realsense_camera::IsPowered::Response & res)
{
if (rs_is_device_streaming(rs_device_, 0) == 1)
{
res.is_powered = true;
}
else
{
res.is_powered = false;
}
return true;
}
/*
* Set Power Camera service
*/
bool BaseNodelet::setPowerCameraService(realsense_camera::SetPower::Request & req,
realsense_camera::SetPower::Response & res)
{
res.success = true;
if (req.power_on == true)
{
ROS_INFO_STREAM(nodelet_name_ << " - " << startCamera());
}
else
{
if (rs_is_device_streaming(rs_device_, 0) == 0)
{
ROS_INFO_STREAM(nodelet_name_ << " - Camera is already Stopped");
}
else
{
if (checkForSubscriber() == false)
{
ROS_INFO_STREAM(nodelet_name_ << " - " << stopCamera());
}
else
{
ROS_INFO_STREAM(nodelet_name_ << " - Cannot stop the camera. Nodelet has subscriber.");
res.success = false;
}
}
}
return res.success;
}
/*
* Force Power Camera service
*/
bool BaseNodelet::forcePowerCameraService(realsense_camera::ForcePower::Request & req,
realsense_camera::ForcePower::Response & res)
{
if (req.power_on == true)
{
ROS_INFO_STREAM(nodelet_name_ << " - " << startCamera());
}
else
{
ROS_INFO_STREAM(nodelet_name_ << " - " << stopCamera());
}
return true;
}
/*
* Get the options supported by the camera along with their min, max and step values.
*/
void BaseNodelet::getCameraOptions()
{
for (int i = 0; i < RS_OPTION_COUNT; ++i)
{
CameraOptions o = { (rs_option) i };
if (rs_device_supports_option(rs_device_, o.opt, &rs_error_))
{
rs_get_device_option_range(rs_device_, o.opt, &o.min, &o.max, &o.step, 0);
// Skip the camera options where min and max values are the same.
if (o.min != o.max)
{
o.value = rs_get_device_option(rs_device_, o.opt, 0);
camera_options_.push_back(o);
}
}
}
}
/*
* Set the static camera options.
*/
void BaseNodelet::setStaticCameraOptions(std::vector<std::string> dynamic_params)
{
ROS_INFO_STREAM(nodelet_name_ << " - Setting static camera options");
// Iterate through the supported camera options
for (CameraOptions o: camera_options_)
{
std::string opt_name = rs_option_to_string(o.opt);
bool found = false;
for (std::string param_name: dynamic_params)
{
std::transform(opt_name.begin(), opt_name.end(), opt_name.begin(), ::tolower);
if (opt_name.compare(param_name) == 0)
{
found = true;
break;
}
}
// Skip the dynamic options and set only the static camera options.
if (found == false)
{
std::string key;
double val;
if (pnh_.searchParam(opt_name, key))
{
double opt_val;
pnh_.getParam(key, val);
// Validate and set the input values within the min-max range
if (val < o.min)
{
opt_val = o.min;
}
else if (val > o.max)
{
opt_val = o.max;
}
else
{
opt_val = val;
}
ROS_DEBUG_STREAM(nodelet_name_ << " - " << opt_name << " = " << opt_val);
rs_set_device_option(rs_device_, o.opt, opt_val, &rs_error_);
checkError();
}
}
}
}
/*
* Set up the callbacks for the camera streams
*/
void BaseNodelet::setFrameCallbacks()
{
depth_frame_handler_ = [&](rs::frame frame)
{
publishTopic(RS_STREAM_DEPTH, frame);
if (enable_pointcloud_ == true)
{
publishPCTopic();
}
};
color_frame_handler_ = [&](rs::frame frame)
{
publishTopic(RS_STREAM_COLOR, frame);
};
ir_frame_handler_ = [&](rs::frame frame)
{
publishTopic(RS_STREAM_INFRARED, frame);
};
rs_set_frame_callback_cpp(rs_device_, RS_STREAM_DEPTH, new rs::frame_callback(depth_frame_handler_), &rs_error_);
checkError();
rs_set_frame_callback_cpp(rs_device_, RS_STREAM_COLOR, new rs::frame_callback(color_frame_handler_), &rs_error_);
checkError();
rs_set_frame_callback_cpp(rs_device_, RS_STREAM_INFRARED, new rs::frame_callback(ir_frame_handler_), &rs_error_);
checkError();
}
/*
* Set the streams according to their corresponding flag values.
*/
void BaseNodelet::setStreams()
{
// Enable streams
for (int stream=0; stream < STREAM_COUNT; stream++)
{
if (enable_[stream] == true)
{
enableStream(static_cast<rs_stream>(stream), width_[stream], height_[stream], format_[stream], fps_[stream]);
}
else if (enable_[stream] == false)
{
disableStream(static_cast<rs_stream>(stream));
}
}
}
/*
* Enable individual streams.
*/
void BaseNodelet::enableStream(rs_stream stream_index, int width, int height, rs_format format, int fps)
{
if (rs_is_stream_enabled(rs_device_, stream_index, 0) == 0)
{
if (mode_.compare("manual") == 0)
{
ROS_INFO_STREAM(nodelet_name_ << " - Enabling " << STREAM_DESC[stream_index] << " in manual mode");
rs_enable_stream(rs_device_, stream_index, width, height, format, fps, &rs_error_);
checkError();
}
else
{
ROS_INFO_STREAM(nodelet_name_ << " - Enabling " << STREAM_DESC[stream_index] << " in preset mode");
rs_enable_stream_preset(rs_device_, stream_index, RS_PRESET_BEST_QUALITY, &rs_error_);
checkError();
}
}
if (camera_info_ptr_[stream_index] == NULL)
{
// Allocate image resources
getStreamCalibData(stream_index);
step_[stream_index] = camera_info_ptr_[stream_index]->width * unit_step_size_[stream_index];
image_[stream_index] = cv::Mat(camera_info_ptr_[stream_index]->height,
camera_info_ptr_[stream_index]->width, cv_type_[stream_index], cv::Scalar(0, 0, 0));
}
ts_[stream_index] = -1;
}
/*
* Prepare camera_info for each enabled stream.
*/
void BaseNodelet::getStreamCalibData(rs_stream stream_index)
{
rs_intrinsics intrinsic;
rs_get_stream_intrinsics(rs_device_, stream_index, &intrinsic, &rs_error_);
if (rs_error_)
{
ROS_ERROR_STREAM(nodelet_name_ << " - Verify camera firmware version and/or calibration data!");
}
checkError();
sensor_msgs::CameraInfo * camera_info = new sensor_msgs::CameraInfo();
camera_info_ptr_[stream_index] = sensor_msgs::CameraInfoPtr (camera_info);
camera_info->header.frame_id = optical_frame_id_[stream_index];
camera_info->width = intrinsic.width;
camera_info->height = intrinsic.height;
camera_info->K.at(0) = intrinsic.fx;
camera_info->K.at(2) = intrinsic.ppx;
camera_info->K.at(4) = intrinsic.fy;
camera_info->K.at(5) = intrinsic.ppy;
camera_info->K.at(8) = 1;
camera_info->P.at(0) = camera_info->K.at(0);
camera_info->P.at(1) = 0;
camera_info->P.at(2) = camera_info->K.at(2);
camera_info->P.at(3) = 0;
camera_info->P.at(4) = 0;
camera_info->P.at(5) = camera_info->K.at(4);
camera_info->P.at(6) = camera_info->K.at(5);
camera_info->P.at(7) = 0;
camera_info->P.at(8) = 0;
camera_info->P.at(9) = 0;
camera_info->P.at(10) = 1;
camera_info->P.at(11) = 0;
if (stream_index == RS_STREAM_DEPTH)
{
// set depth to color translation values in Projection matrix (P)
rs_extrinsics z_extrinsic;
rs_get_device_extrinsics(rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_);
if (rs_error_)
{
ROS_ERROR_STREAM(nodelet_name_ << " - Verify camera is calibrated!");
}
checkError();
camera_info->P.at(3) = z_extrinsic.translation[0]; // Tx
camera_info->P.at(7) = z_extrinsic.translation[1]; // Ty
camera_info->P.at(11) = z_extrinsic.translation[2]; // Tz
}
camera_info->distortion_model = "plumb_bob";
// set R (rotation matrix) values to identity matrix
camera_info->R.at(0) = 1.0;
camera_info->R.at(1) = 0.0;
camera_info->R.at(2) = 0.0;
camera_info->R.at(3) = 0.0;
camera_info->R.at(4) = 1.0;
camera_info->R.at(5) = 0.0;
camera_info->R.at(6) = 0.0;
camera_info->R.at(7) = 0.0;
camera_info->R.at(8) = 1.0;
for (int i = 0; i < 5; i++)
{
camera_info->D.push_back(intrinsic.coeffs[i]);
}
}
/*
* Disable individual streams.
*/
void BaseNodelet::disableStream(rs_stream stream_index)
{
if (rs_is_stream_enabled(rs_device_, stream_index, 0) == 1)
{
ROS_INFO_STREAM(nodelet_name_ << " - Disabling " << STREAM_DESC[stream_index] << " stream");
rs_disable_stream(rs_device_, stream_index, &rs_error_);
checkError();
}
}
/*
* Start camera.
*/
std::string BaseNodelet::startCamera()
{
if (rs_is_device_streaming(rs_device_, 0) == 0)
{
ROS_INFO_STREAM(nodelet_name_ << " - Starting camera");
// Set up the callbacks for each stream
setFrameCallbacks();
rs_start_device(rs_device_, &rs_error_);
checkError();
camera_start_ts_ = ros::Time::now();
return "Camera Started Successfully";
}
return "Camera is already Started";
}
/*
* Stop camera.
*/
std::string BaseNodelet::stopCamera()
{
if (rs_is_device_streaming(rs_device_, 0) == 1)
{
ROS_INFO_STREAM(nodelet_name_ << " - Stopping camera");
rs_stop_device(rs_device_, 0);
checkError();
return "Camera Stopped Successfully";
}
return "Camera is already Stopped";
}
/*
* Copy frame data from realsense to member cv images.
*/
void BaseNodelet::setImageData(rs_stream stream_index, rs::frame & frame)
{
if (stream_index == RS_STREAM_DEPTH)
{
// fill depth buffer
image_depth16_ = reinterpret_cast<const uint16_t *>(frame.get_data());
float depth_scale_meters = rs_get_device_depth_scale(rs_device_, &rs_error_);
if (depth_scale_meters == MILLIMETER_METERS)
{
image_[stream_index].data = (unsigned char *) image_depth16_;
}
else
{
cvWrapper_ = cv::Mat(image_[stream_index].size(), cv_type_[stream_index], (void *) image_depth16_,
step_[stream_index]);
cvWrapper_.convertTo(image_[stream_index], cv_type_[stream_index],
static_cast<double>(depth_scale_meters) / static_cast<double>(MILLIMETER_METERS));
}
}
else
{
image_[stream_index].data = (unsigned char *) (frame.get_data());
}
}
/*
* Set depth enable
*/
void BaseNodelet::setDepthEnable(bool &enable_depth)
{
// Set flags
if (enable_depth == false)
{
if (enable_[RS_STREAM_COLOR] == false)
{
ROS_INFO_STREAM(nodelet_name_ << " - Color stream is also disabled. Cannot disable depth stream");
enable_depth = true;
}
else
{
enable_[RS_STREAM_DEPTH] = false;
}
}
else
{
enable_[RS_STREAM_DEPTH] = true;
}
if (enable_[RS_STREAM_DEPTH] != rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0))
{
stopCamera();
setStreams();
startCamera();
}
}
/*
* Publish topic.
*/
void BaseNodelet::publishTopic(rs_stream stream_index, rs::frame &frame) try
{
// mutex to ensure only one frame per stream is processed at a time
std::unique_lock<std::mutex> lock(frame_mutex_[stream_index]);
double frame_ts = frame.get_timestamp();
if (ts_[stream_index] != frame_ts) // Publish frames only if its not duplicate
{
setImageData(stream_index, frame);
// Publish stream only if there is at least one subscriber.
if (camera_publisher_[stream_index].getNumSubscribers() > 0)
{
sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(),
encoding_[stream_index],
image_[stream_index]).toImageMsg();
msg->header.frame_id = optical_frame_id_[stream_index];
msg->header.stamp = ros::Time(camera_start_ts_) + ros::Duration(frame_ts * 0.001); // Publish timestamp to synchronize frames.
msg->width = image_[stream_index].cols;
msg->height = image_[stream_index].rows;
msg->is_bigendian = false;
msg->step = step_[stream_index];
camera_info_ptr_[stream_index]->header.stamp = msg->header.stamp;
camera_publisher_[stream_index].publish (msg, camera_info_ptr_[stream_index]);
}
}
ts_[stream_index] = frame_ts;
}
catch(const rs::error & e)
{
ROS_ERROR_STREAM(nodelet_name_ << " - " << "RealSense error calling "
<< e.get_failed_function() << "(" << e.get_failed_args() << "):\n "
<< e.what());
ros::shutdown();
}
catch(const std::exception & e)
{
ROS_ERROR_STREAM(nodelet_name_ << " - " << e.what());
ros::shutdown();
}
catch(...)
{
ROS_ERROR_STREAM(nodelet_name_ << " - Caught unknown expection...shutting down!");
ros::shutdown();
}
/*
* Publish pointcloud topic.
*/
void BaseNodelet::publishPCTopic()
{
cv::Mat & image_color = image_[RS_STREAM_COLOR];
// Publish pointcloud only if there is at least one subscriber.
if (pointcloud_publisher_.getNumSubscribers() > 0 && rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0) == 1)
{
rs_intrinsics color_intrinsic;
rs_extrinsics z_extrinsic;
rs_intrinsics z_intrinsic;
rs_get_stream_intrinsics(rs_device_, RS_STREAM_DEPTH, &z_intrinsic, &rs_error_);
checkError();
if (enable_[RS_STREAM_COLOR] == true)
{
rs_get_stream_intrinsics(rs_device_, RS_STREAM_COLOR, &color_intrinsic, &rs_error_);
checkError();
rs_get_device_extrinsics(rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_);
checkError();
}
// Convert pointcloud from the camera to pointcloud object for ROS.
sensor_msgs::PointCloud2 msg_pointcloud;
msg_pointcloud.width = width_[RS_STREAM_DEPTH];
msg_pointcloud.height = height_[RS_STREAM_DEPTH];
msg_pointcloud.header.stamp = ros::Time::now();
msg_pointcloud.is_dense = true;
sensor_msgs::PointCloud2Modifier modifier(msg_pointcloud);
modifier.setPointCloud2Fields(4, "x", 1,
sensor_msgs::PointField::FLOAT32, "y", 1,
sensor_msgs::PointField::FLOAT32, "z", 1,
sensor_msgs::PointField::FLOAT32, "rgb", 1,
sensor_msgs::PointField::FLOAT32);
modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
sensor_msgs::PointCloud2Iterator<float>iter_x(msg_pointcloud, "x");
sensor_msgs::PointCloud2Iterator<float>iter_y(msg_pointcloud, "y");
sensor_msgs::PointCloud2Iterator<float>iter_z(msg_pointcloud, "z");
sensor_msgs::PointCloud2Iterator<uint8_t>iter_r(msg_pointcloud, "r");
sensor_msgs::PointCloud2Iterator<uint8_t>iter_g(msg_pointcloud, "g");
sensor_msgs::PointCloud2Iterator<uint8_t>iter_b(msg_pointcloud, "b");
float depth_point[3], color_point[3], color_pixel[2], scaled_depth;
unsigned char *color_data = image_color.data;
checkError();// Default value is 0.001
float depth_scale_meters = rs_get_device_depth_scale(rs_device_, &rs_error_);
// Fill the PointCloud2 fields.
for (int y = 0; y < z_intrinsic.height; y++)
{
for (int x = 0; x < z_intrinsic.width; x++)
{
scaled_depth = static_cast<float>(*image_depth16_) * depth_scale_meters;
float depth_pixel[2] = {static_cast<float>(x), static_cast<float>(y)};
rs_deproject_pixel_to_point(depth_point, &z_intrinsic, depth_pixel, scaled_depth);
if (depth_point[2] <= 0.0f || depth_point[2] > max_z_)
{
depth_point[0] = 0.0f;
depth_point[1] = 0.0f;
depth_point[2] = 0.0f;
}
*iter_x = depth_point[0];
*iter_y = depth_point[1];
*iter_z = depth_point[2];
// Default to white color.
*iter_r = static_cast<uint8_t>(255);
*iter_g = static_cast<uint8_t>(255);
*iter_b = static_cast<uint8_t>(255);
if (enable_[RS_STREAM_COLOR] == true)
{
rs_transform_point_to_point(color_point, &z_extrinsic, depth_point);
rs_project_point_to_pixel(color_pixel, &color_intrinsic, color_point);
if (color_pixel[1] < 0.0f || color_pixel[1] > image_color.rows
|| color_pixel[0] < 0.0f || color_pixel[0] > image_color.cols)
{
// For out of bounds color data, default to a shade of blue in order to visually distinguish holes.
// This color value is same as the librealsense out of bounds color value.
*iter_r = static_cast<uint8_t>(96);
*iter_g = static_cast<uint8_t>(157);
*iter_b = static_cast<uint8_t>(198);
}
else
{
int i = static_cast<int>(color_pixel[0]);
int j = static_cast<int>(color_pixel[1]);
*iter_r = static_cast<uint8_t>(color_data[i * 3 + j * image_color.cols * 3]);
*iter_g = static_cast<uint8_t>(color_data[i * 3 + j * image_color.cols * 3 + 1]);
*iter_b = static_cast<uint8_t>(color_data[i * 3 + j * image_color.cols * 3 + 2]);
}
}
image_depth16_++;
++iter_x; ++iter_y; ++iter_z; ++iter_r; ++iter_g; ++iter_b;
}
}
msg_pointcloud.header.frame_id = optical_frame_id_[RS_STREAM_DEPTH];
pointcloud_publisher_.publish(msg_pointcloud);
}
}
/*
* Get the camera extrinsics
*/
void BaseNodelet::getCameraExtrinsics()
{
// Get offset between base frame and depth frame
rs_get_device_extrinsics(rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &color2depth_extrinsic_, &rs_error_);
if (rs_error_)
{
ROS_ERROR_STREAM(nodelet_name_ << " - Verify camera is calibrated!");
}
checkError();
// Get offset between base frame and infrared frame
rs_get_device_extrinsics(rs_device_, RS_STREAM_INFRARED, RS_STREAM_COLOR, &color2ir_extrinsic_, &rs_error_);
if (rs_error_)
{
ROS_ERROR_STREAM(nodelet_name_ << " - Verify camera is calibrated!");
}
checkError();
}
/*
* Publish Static transforms.
*/
void BaseNodelet::publishStaticTransforms()
{
// Publish transforms for the cameras
ROS_INFO_STREAM(nodelet_name_ << " - Publishing camera transforms (/tf_static)");
tf::Quaternion q_c2co;
tf::Quaternion q_d2do;
tf::Quaternion q_i2io;
geometry_msgs::TransformStamped b2d_msg;
geometry_msgs::TransformStamped d2do_msg;
geometry_msgs::TransformStamped b2c_msg;
geometry_msgs::TransformStamped c2co_msg;
geometry_msgs::TransformStamped b2i_msg;