-
Notifications
You must be signed in to change notification settings - Fork 220
/
k4a_ros_device.cpp
1525 lines (1291 loc) · 55.1 KB
/
k4a_ros_device.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) Microsoft Corporation. All rights reserved.
// Licensed under the MIT License.
// Associated header
//
#include "azure_kinect_ros_driver/k4a_ros_device.h"
// System headers
//
#include <thread>
// Library headers
//
#include <angles/angles.h>
#include <cv_bridge/cv_bridge.h>
#include <k4a/k4a.h>
#include <sensor_msgs/distortion_models.h>
#include <sensor_msgs/image_encodings.h>
#include <sensor_msgs/point_cloud2_iterator.h>
#include <k4a/k4a.hpp>
#include <unordered_map>
// Project headers
//
#include "azure_kinect_ros_driver/k4a_ros_types.h"
using namespace ros;
using namespace sensor_msgs;
using namespace image_transport;
using namespace std;
static const std::unordered_map<k4a_color_resolution_t, std::string> color_mode_string = {
{K4A_COLOR_RESOLUTION_720P, "720P"},
{K4A_COLOR_RESOLUTION_1080P, "1080P"},
{K4A_COLOR_RESOLUTION_1440P, "1440P"},
{K4A_COLOR_RESOLUTION_1536P, "1536P"},
{K4A_COLOR_RESOLUTION_2160P, "2160P"},
{K4A_COLOR_RESOLUTION_3072P, "3072P"},
};
static const std::unordered_map<k4a_depth_mode_t, std::string> depth_mode_string = {
{K4A_DEPTH_MODE_NFOV_2X2BINNED, "NFOV_2X2BINNED"},
{K4A_DEPTH_MODE_NFOV_UNBINNED, "NFOV_UNBINNED"},
{K4A_DEPTH_MODE_WFOV_2X2BINNED, "WFOV_2X2BINNED"},
{K4A_DEPTH_MODE_WFOV_UNBINNED, "WFOV_UNBINNED"},
{K4A_DEPTH_MODE_PASSIVE_IR, "PASSIVE_IR"},
};
#if defined(K4A_BODY_TRACKING)
using namespace visualization_msgs;
#endif
K4AROSDevice::K4AROSDevice(const NodeHandle& n, const NodeHandle& p)
: k4a_device_(nullptr),
k4a_playback_handle_(nullptr),
// clang-format off
#if defined(K4A_BODY_TRACKING)
k4abt_tracker_(nullptr),
k4abt_tracker_queue_size_(0),
#endif
// clang-format on
node_(n),
private_node_(p),
node_rgb_("rgb"),
node_ir_("ir"),
image_transport_(n),
last_capture_time_usec_(0),
last_imu_time_usec_(0),
imu_stream_end_of_file_(false)
{
// Collect ROS parameters from the param server or from the command line
#define LIST_ENTRY(param_variable, param_help_string, param_type, param_default_val) \
private_node_.param(#param_variable, params_.param_variable, param_default_val);
ROS_PARAM_LIST
#undef LIST_ENTRY
if (!params_.recording_file.empty())
{
ROS_INFO("Node is started in playback mode");
ROS_INFO_STREAM("Try to open recording file " << params_.recording_file);
// Open recording file and print its length
k4a_playback_handle_ = k4a::playback::open(params_.recording_file.c_str());
auto recording_length = k4a_playback_handle_.get_recording_length();
ROS_INFO_STREAM("Successfully openend recording file. Recording is " << recording_length.count() / 1000000
<< " seconds long");
if (!k4a_playback_handle_.get_tag("K4A_DEVICE_SERIAL_NUMBER", &serial_number_))
{
serial_number_ = {};
ROS_ERROR("Cannot read serial number from recording.");
}
// Get the recordings configuration to overwrite node parameters
k4a_record_configuration_t record_config = k4a_playback_handle_.get_record_configuration();
// Overwrite fps param with recording configuration for a correct loop rate in the frame publisher thread
switch (record_config.camera_fps)
{
case K4A_FRAMES_PER_SECOND_5:
params_.fps = 5;
break;
case K4A_FRAMES_PER_SECOND_15:
params_.fps = 15;
break;
case K4A_FRAMES_PER_SECOND_30:
params_.fps = 30;
break;
default:
break;
};
// Disable color if the recording has no color track
if (params_.color_enabled && !record_config.color_track_enabled)
{
ROS_WARN("Disabling color and rgb_point_cloud because recording has no color track");
params_.color_enabled = false;
params_.rgb_point_cloud = false;
}
// This is necessary because at the moment there are only checks in place which use BgraPixel size
else if (params_.color_enabled && record_config.color_track_enabled)
{
if (params_.color_format == "jpeg" && record_config.color_format != K4A_IMAGE_FORMAT_COLOR_MJPG)
{
ROS_FATAL("Converting color images to K4A_IMAGE_FORMAT_COLOR_MJPG is not supported.");
ros::requestShutdown();
return;
}
if (params_.color_format == "bgra" && record_config.color_format != K4A_IMAGE_FORMAT_COLOR_BGRA32)
{
k4a_playback_handle_.set_color_conversion(K4A_IMAGE_FORMAT_COLOR_BGRA32);
}
}
// Disable depth if the recording has neither ir track nor depth track
if (!record_config.ir_track_enabled && !record_config.depth_track_enabled)
{
if (params_.depth_enabled)
{
ROS_WARN("Disabling depth because recording has neither ir track nor depth track");
params_.depth_enabled = false;
}
}
// Disable depth if the recording has no depth track
if (!record_config.depth_track_enabled)
{
if (params_.point_cloud)
{
ROS_WARN("Disabling point cloud because recording has no depth track");
params_.point_cloud = false;
}
if (params_.rgb_point_cloud)
{
ROS_WARN("Disabling rgb point cloud because recording has no depth track");
params_.rgb_point_cloud = false;
}
}
}
else
{
// Print all parameters
ROS_INFO("K4A Parameters:");
params_.Print();
// Setup the K4A device
uint32_t k4a_device_count = k4a::device::get_installed_count();
ROS_INFO_STREAM("Found " << k4a_device_count << " sensors");
if (params_.sensor_sn != "")
{
ROS_INFO_STREAM("Searching for sensor with serial number: " << params_.sensor_sn);
}
else
{
ROS_INFO("No serial number provided: picking first sensor");
ROS_WARN_COND(k4a_device_count > 1, "Multiple sensors connected! Picking first sensor.");
}
for (uint32_t i = 0; i < k4a_device_count; i++)
{
k4a::device device;
try
{
device = k4a::device::open(i);
}
catch (exception)
{
ROS_ERROR_STREAM("Failed to open K4A device at index " << i);
continue;
}
ROS_INFO_STREAM("K4A[" << i << "] : " << device.get_serialnum());
// Try to match serial number
if (params_.sensor_sn != "")
{
if (device.get_serialnum() == params_.sensor_sn)
{
k4a_device_ = std::move(device);
break;
}
}
// Pick the first device
else if (i == 0)
{
k4a_device_ = std::move(device);
break;
}
}
if (!k4a_device_)
{
ROS_ERROR("Failed to open a K4A device. Cannot continue.");
return;
}
serial_number_ = k4a_device_.get_serialnum();
ROS_INFO_STREAM("K4A Serial Number: " << serial_number_);
k4a_hardware_version_t version_info = k4a_device_.get_version();
ROS_INFO("RGB Version: %d.%d.%d", version_info.rgb.major, version_info.rgb.minor, version_info.rgb.iteration);
ROS_INFO("Depth Version: %d.%d.%d", version_info.depth.major, version_info.depth.minor,
version_info.depth.iteration);
ROS_INFO("Audio Version: %d.%d.%d", version_info.audio.major, version_info.audio.minor,
version_info.audio.iteration);
ROS_INFO("Depth Sensor Version: %d.%d.%d", version_info.depth_sensor.major, version_info.depth_sensor.minor,
version_info.depth_sensor.iteration);
}
// Register our topics
if (params_.color_format == "jpeg")
{
// JPEG images are directly published on 'rgb/image_raw/compressed' so that
// others can subscribe to 'rgb/image_raw' with compressed_image_transport.
// This technique is described in:
// http://wiki.ros.org/compressed_image_transport#Publishing_compressed_images_directly
rgb_jpeg_publisher_ = node_.advertise<CompressedImage>(node_.resolveName("rgb/image_raw") + "/compressed", 1);
}
else if (params_.color_format == "bgra")
{
rgb_raw_publisher_ = image_transport_.advertise("rgb/image_raw", 1);
}
rgb_raw_camerainfo_publisher_ = node_.advertise<CameraInfo>("rgb/camera_info", 1);
static const std::string depth_raw_topic = "depth/image_raw";
static const std::string depth_rect_topic = "depth_to_rgb/image_raw";
if (params_.depth_unit == sensor_msgs::image_encodings::TYPE_16UC1) {
// set lowest PNG compression for maximum FPS
node_.setParam(node_.resolveName(depth_raw_topic) + "/compressed/format", "png");
node_.setParam(node_.resolveName(depth_raw_topic) + "/compressed/png_level", 1);
node_.setParam(node_.resolveName(depth_rect_topic) + "/compressed/format", "png");
node_.setParam(node_.resolveName(depth_rect_topic) + "/compressed/png_level", 1);
}
depth_raw_publisher_ = image_transport_.advertise(depth_raw_topic, 1);
depth_raw_camerainfo_publisher_ = node_.advertise<CameraInfo>("depth/camera_info", 1);
depth_rect_publisher_ = image_transport_.advertise(depth_rect_topic, 1);
depth_rect_camerainfo_publisher_ = node_.advertise<CameraInfo>("depth_to_rgb/camera_info", 1);
rgb_rect_publisher_ = image_transport_.advertise("rgb_to_depth/image_raw", 1);
rgb_rect_camerainfo_publisher_ = node_.advertise<CameraInfo>("rgb_to_depth/camera_info", 1);
ir_raw_publisher_ = image_transport_.advertise("ir/image_raw", 1);
ir_raw_camerainfo_publisher_ = node_.advertise<CameraInfo>("ir/camera_info", 1);
imu_orientation_publisher_ = node_.advertise<Imu>("imu", 200);
if (params_.point_cloud || params_.rgb_point_cloud) {
pointcloud_publisher_ = node_.advertise<PointCloud2>("points2", 1);
}
if (k4a_playback_handle_) {
// override color and depth mode configuration with settings from log file
const k4a_color_resolution_t cm = k4a_playback_handle_.get_record_configuration().color_resolution;
if (cm != K4A_COLOR_RESOLUTION_OFF) {
params_.color_resolution = color_mode_string.at(cm);
}
const k4a_depth_mode_t dm = k4a_playback_handle_.get_record_configuration().depth_mode;
if (dm != K4A_DEPTH_MODE_OFF) {
params_.depth_mode = depth_mode_string.at(dm);
}
}
// load calibration file from provided path or use default camera calibration URL at $HOME/.ros/camera_info/<cname>.yaml
const std::string calibration_file_name_rgb = "azure_kinect_rgb_"+serial_number_+"_"+params_.color_resolution;
const std::string calibration_file_name_ir = "azure_kinect_ir_"+serial_number_+"_"+params_.depth_mode;
const std::string calibration_url_rgb = params_.calibration_url.empty() ? std::string{} : params_.calibration_url + '/' + calibration_file_name_rgb + ".yaml";
const std::string calibration_url_ir = params_.calibration_url.empty() ? std::string{} : params_.calibration_url + '/' + calibration_file_name_ir + ".yaml";
ci_mngr_rgb_ = std::make_shared<camera_info_manager::CameraInfoManager>(node_rgb_, calibration_file_name_rgb, calibration_url_rgb);
ci_mngr_ir_ = std::make_shared<camera_info_manager::CameraInfoManager>(node_ir_, calibration_file_name_ir, calibration_url_ir);
#if defined(K4A_BODY_TRACKING)
if (params_.body_tracking_enabled) {
body_marker_publisher_ = node_.advertise<MarkerArray>("body_tracking_data", 1);
body_index_map_publisher_ = image_transport_.advertise("body_index_map/image_raw", 1);
}
#endif
}
K4AROSDevice::~K4AROSDevice()
{
// Start tearing down the publisher threads
running_ = false;
#if defined(K4A_BODY_TRACKING)
// Join the publisher thread
ROS_INFO("Joining body publisher thread");
body_publisher_thread_.join();
ROS_INFO("Body publisher thread joined");
#endif
// Join the publisher thread
ROS_INFO("Joining camera publisher thread");
frame_publisher_thread_.join();
ROS_INFO("Camera publisher thread joined");
// Join the publisher thread
ROS_INFO("Joining IMU publisher thread");
imu_publisher_thread_.join();
ROS_INFO("IMU publisher thread joined");
stopCameras();
stopImu();
if (k4a_playback_handle_)
{
k4a_playback_handle_.close();
}
#if defined(K4A_BODY_TRACKING)
if (k4abt_tracker_)
{
k4abt_tracker_.shutdown();
}
#endif
}
k4a_result_t K4AROSDevice::startCameras()
{
k4a_device_configuration_t k4a_configuration = K4A_DEVICE_CONFIG_INIT_DISABLE_ALL;
if (k4a_device_)
{
k4a_result_t result = params_.GetDeviceConfig(&k4a_configuration);
if (result != K4A_RESULT_SUCCEEDED)
{
ROS_ERROR("Failed to generate a device configuration. Not starting camera!");
return result;
}
// Now that we have a proposed camera configuration, we can
// initialize the class which will take care of device calibration information
calibration_data_.initialize(k4a_device_, k4a_configuration.depth_mode, k4a_configuration.color_resolution,
params_);
}
else if (k4a_playback_handle_)
{
// initialize the class which will take care of device calibration information from the playback_handle
calibration_data_.initialize(k4a_playback_handle_, params_);
}
#if defined(K4A_BODY_TRACKING)
// When calibration is initialized the body tracker can be created with the device calibration
if (params_.body_tracking_enabled)
{
k4abt_tracker_ = k4abt::tracker::create(calibration_data_.k4a_calibration_);
k4abt_tracker_.set_temporal_smoothing(params_.body_tracking_smoothing_factor);
}
#endif
if (k4a_device_)
{
ROS_INFO_STREAM("STARTING CAMERAS");
k4a_device_.start_cameras(&k4a_configuration);
}
// Cannot assume the device timestamp begins increasing upon starting the cameras.
// If we set the time base here, depending on the machine performance, the new timestamp
// would lag the value of ros::Time::now() by at least 0.5 secs which is much larger than
// the real transmission delay as can be observed using the rqt_plot tool.
// start_time_ = ros::Time::now();
// Prevent the worker thread from exiting immediately
running_ = true;
// Start the thread that will poll the cameras and publish frames
frame_publisher_thread_ = thread(&K4AROSDevice::framePublisherThread, this);
#if defined(K4A_BODY_TRACKING)
body_publisher_thread_ = thread(&K4AROSDevice::bodyPublisherThread, this);
#endif
return K4A_RESULT_SUCCEEDED;
}
k4a_result_t K4AROSDevice::startImu()
{
if (k4a_device_)
{
ROS_INFO_STREAM("STARTING IMU");
k4a_device_.start_imu();
}
// Start the IMU publisher thread
imu_publisher_thread_ = thread(&K4AROSDevice::imuPublisherThread, this);
return K4A_RESULT_SUCCEEDED;
}
void K4AROSDevice::stopCameras()
{
if (k4a_device_)
{
// Stop the K4A SDK
ROS_INFO("Stopping K4A device");
k4a_device_.stop_cameras();
ROS_INFO("K4A device stopped");
}
}
void K4AROSDevice::stopImu()
{
if (k4a_device_)
{
k4a_device_.stop_imu();
}
}
k4a_result_t K4AROSDevice::getDepthFrame(const k4a::capture& capture, sensor_msgs::ImagePtr& depth_image,
bool rectified = false)
{
k4a::image k4a_depth_frame = capture.get_depth_image();
if (!k4a_depth_frame)
{
ROS_ERROR("Cannot render depth frame: no frame");
return K4A_RESULT_FAILED;
}
if (rectified)
{
calibration_data_.k4a_transformation_.depth_image_to_color_camera(k4a_depth_frame,
&calibration_data_.transformed_depth_image_);
return renderDepthToROS(depth_image, calibration_data_.transformed_depth_image_);
}
return renderDepthToROS(depth_image, k4a_depth_frame);
}
k4a_result_t K4AROSDevice::renderDepthToROS(sensor_msgs::ImagePtr& depth_image, k4a::image& k4a_depth_frame)
{
cv::Mat depth_frame_buffer_mat(k4a_depth_frame.get_height_pixels(), k4a_depth_frame.get_width_pixels(), CV_16UC1,
k4a_depth_frame.get_buffer());
std::string encoding;
if (params_.depth_unit == sensor_msgs::image_encodings::TYPE_32FC1) {
// convert from 16 bit integer millimetre to 32 bit float metre
depth_frame_buffer_mat.convertTo(depth_frame_buffer_mat, CV_32FC1, 1.0 / 1000.0f);
encoding = sensor_msgs::image_encodings::TYPE_32FC1;
}
else if (params_.depth_unit == sensor_msgs::image_encodings::TYPE_16UC1) {
// source data is already in 'K4A_IMAGE_FORMAT_DEPTH16' format
encoding = sensor_msgs::image_encodings::TYPE_16UC1;
}
else {
ROS_ERROR_STREAM("Invalid depth unit: " << params_.depth_unit);
return K4A_RESULT_FAILED;
}
depth_image =
cv_bridge::CvImage(std_msgs::Header(), encoding, depth_frame_buffer_mat).toImageMsg();
return K4A_RESULT_SUCCEEDED;
}
k4a_result_t K4AROSDevice::getIrFrame(const k4a::capture& capture, sensor_msgs::ImagePtr& ir_image)
{
k4a::image k4a_ir_frame = capture.get_ir_image();
if (!k4a_ir_frame)
{
ROS_ERROR("Cannot render IR frame: no frame");
return K4A_RESULT_FAILED;
}
return renderIrToROS(ir_image, k4a_ir_frame);
}
k4a_result_t K4AROSDevice::renderIrToROS(sensor_msgs::ImagePtr& ir_image, k4a::image& k4a_ir_frame)
{
cv::Mat ir_buffer_mat(k4a_ir_frame.get_height_pixels(), k4a_ir_frame.get_width_pixels(), CV_16UC1,
k4a_ir_frame.get_buffer());
// Rescale the image to mono8 for visualization and usage for visual(-inertial) odometry.
if (params_.rescale_ir_to_mono8)
{
cv::Mat new_image(k4a_ir_frame.get_height_pixels(), k4a_ir_frame.get_width_pixels(), CV_8UC1);
// Use a scaling factor to re-scale the image. If using the illuminators, a value of 1 is appropriate.
// If using PASSIVE_IR, then a value of 10 is more appropriate; k4aviewer does a similar conversion.
ir_buffer_mat.convertTo(new_image, CV_8UC1, params_.ir_mono8_scaling_factor);
ir_image = cv_bridge::CvImage(std_msgs::Header(), sensor_msgs::image_encodings::MONO8, new_image).toImageMsg();
}
else
{
ir_image = cv_bridge::CvImage(std_msgs::Header(), sensor_msgs::image_encodings::MONO16, ir_buffer_mat).toImageMsg();
}
return K4A_RESULT_SUCCEEDED;
}
k4a_result_t K4AROSDevice::getJpegRgbFrame(const k4a::capture& capture, sensor_msgs::CompressedImagePtr& jpeg_image)
{
k4a::image k4a_jpeg_frame = capture.get_color_image();
if (!k4a_jpeg_frame)
{
ROS_ERROR("Cannot render Jpeg frame: no frame");
return K4A_RESULT_FAILED;
}
const uint8_t* jpeg_frame_buffer = k4a_jpeg_frame.get_buffer();
jpeg_image->format = "bgra8; jpeg compressed bgr8";
jpeg_image->data.assign(jpeg_frame_buffer, jpeg_frame_buffer + k4a_jpeg_frame.get_size());
return K4A_RESULT_SUCCEEDED;
}
k4a_result_t K4AROSDevice::getRbgFrame(const k4a::capture& capture, sensor_msgs::ImagePtr& rgb_image,
bool rectified = false)
{
k4a::image k4a_bgra_frame = capture.get_color_image();
if (!k4a_bgra_frame)
{
ROS_ERROR("Cannot render BGRA frame: no frame");
return K4A_RESULT_FAILED;
}
size_t color_image_size =
static_cast<size_t>(k4a_bgra_frame.get_width_pixels() * k4a_bgra_frame.get_height_pixels()) * sizeof(BgraPixel);
if (k4a_bgra_frame.get_size() != color_image_size)
{
ROS_WARN("Invalid k4a_bgra_frame returned from K4A");
return K4A_RESULT_FAILED;
}
if (rectified)
{
k4a::image k4a_depth_frame = capture.get_depth_image();
calibration_data_.k4a_transformation_.color_image_to_depth_camera(k4a_depth_frame, k4a_bgra_frame,
&calibration_data_.transformed_rgb_image_);
return renderBGRA32ToROS(rgb_image, calibration_data_.transformed_rgb_image_);
}
return renderBGRA32ToROS(rgb_image, k4a_bgra_frame);
}
// Helper function that renders any BGRA K4A frame to a ROS ImagePtr. Useful for rendering intermediary frames
// during debugging of image processing functions
k4a_result_t K4AROSDevice::renderBGRA32ToROS(sensor_msgs::ImagePtr& rgb_image, k4a::image& k4a_bgra_frame)
{
cv::Mat rgb_buffer_mat(k4a_bgra_frame.get_height_pixels(), k4a_bgra_frame.get_width_pixels(), CV_8UC4,
k4a_bgra_frame.get_buffer());
rgb_image = cv_bridge::CvImage(std_msgs::Header(), sensor_msgs::image_encodings::BGRA8, rgb_buffer_mat).toImageMsg();
return K4A_RESULT_SUCCEEDED;
}
k4a_result_t K4AROSDevice::getRgbPointCloudInDepthFrame(const k4a::capture& capture,
sensor_msgs::PointCloud2Ptr& point_cloud)
{
const k4a::image k4a_depth_frame = capture.get_depth_image();
if (!k4a_depth_frame)
{
ROS_ERROR("Cannot render RGB point cloud: no depth frame");
return K4A_RESULT_FAILED;
}
const k4a::image k4a_bgra_frame = capture.get_color_image();
if (!k4a_bgra_frame)
{
ROS_ERROR("Cannot render RGB point cloud: no BGRA frame");
return K4A_RESULT_FAILED;
}
// Transform color image into the depth camera frame:
calibration_data_.k4a_transformation_.color_image_to_depth_camera(k4a_depth_frame, k4a_bgra_frame,
&calibration_data_.transformed_rgb_image_);
// Tranform depth image to point cloud
calibration_data_.k4a_transformation_.depth_image_to_point_cloud(k4a_depth_frame, K4A_CALIBRATION_TYPE_DEPTH,
&calibration_data_.point_cloud_image_);
point_cloud->header.frame_id = calibration_data_.tf_prefix_ + calibration_data_.depth_camera_frame_;
point_cloud->header.stamp = timestampToROS(k4a_depth_frame.get_device_timestamp());
return fillColorPointCloud(calibration_data_.point_cloud_image_, calibration_data_.transformed_rgb_image_,
point_cloud);
}
k4a_result_t K4AROSDevice::getRgbPointCloudInRgbFrame(const k4a::capture& capture,
sensor_msgs::PointCloud2Ptr& point_cloud)
{
k4a::image k4a_depth_frame = capture.get_depth_image();
if (!k4a_depth_frame)
{
ROS_ERROR("Cannot render RGB point cloud: no depth frame");
return K4A_RESULT_FAILED;
}
k4a::image k4a_bgra_frame = capture.get_color_image();
if (!k4a_bgra_frame)
{
ROS_ERROR("Cannot render RGB point cloud: no BGRA frame");
return K4A_RESULT_FAILED;
}
// transform depth image into color camera geometry
calibration_data_.k4a_transformation_.depth_image_to_color_camera(k4a_depth_frame,
&calibration_data_.transformed_depth_image_);
// Tranform depth image to point cloud (note that this is now from the perspective of the color camera)
calibration_data_.k4a_transformation_.depth_image_to_point_cloud(
calibration_data_.transformed_depth_image_, K4A_CALIBRATION_TYPE_COLOR, &calibration_data_.point_cloud_image_);
point_cloud->header.frame_id = calibration_data_.tf_prefix_ + calibration_data_.rgb_camera_frame_;
point_cloud->header.stamp = timestampToROS(k4a_depth_frame.get_device_timestamp());
return fillColorPointCloud(calibration_data_.point_cloud_image_, k4a_bgra_frame, point_cloud);
}
k4a_result_t K4AROSDevice::getPointCloud(const k4a::capture& capture, sensor_msgs::PointCloud2Ptr& point_cloud)
{
k4a::image k4a_depth_frame = capture.get_depth_image();
if (!k4a_depth_frame)
{
ROS_ERROR("Cannot render point cloud: no depth frame");
return K4A_RESULT_FAILED;
}
point_cloud->header.frame_id = calibration_data_.tf_prefix_ + calibration_data_.depth_camera_frame_;
point_cloud->header.stamp = timestampToROS(k4a_depth_frame.get_device_timestamp());
// Tranform depth image to point cloud
calibration_data_.k4a_transformation_.depth_image_to_point_cloud(k4a_depth_frame, K4A_CALIBRATION_TYPE_DEPTH,
&calibration_data_.point_cloud_image_);
return fillPointCloud(calibration_data_.point_cloud_image_, point_cloud);
}
k4a_result_t K4AROSDevice::fillColorPointCloud(const k4a::image& pointcloud_image, const k4a::image& color_image,
sensor_msgs::PointCloud2Ptr& point_cloud)
{
point_cloud->height = pointcloud_image.get_height_pixels();
point_cloud->width = pointcloud_image.get_width_pixels();
point_cloud->is_dense = false;
point_cloud->is_bigendian = false;
const size_t point_count = pointcloud_image.get_height_pixels() * pointcloud_image.get_width_pixels();
const size_t pixel_count = color_image.get_size() / sizeof(BgraPixel);
if (point_count != pixel_count)
{
ROS_WARN("Color and depth image sizes do not match!");
return K4A_RESULT_FAILED;
}
sensor_msgs::PointCloud2Modifier pcd_modifier(*point_cloud);
pcd_modifier.setPointCloud2FieldsByString(2, "xyz", "rgb");
sensor_msgs::PointCloud2Iterator<float> iter_x(*point_cloud, "x");
sensor_msgs::PointCloud2Iterator<float> iter_y(*point_cloud, "y");
sensor_msgs::PointCloud2Iterator<float> iter_z(*point_cloud, "z");
sensor_msgs::PointCloud2Iterator<uint8_t> iter_r(*point_cloud, "r");
sensor_msgs::PointCloud2Iterator<uint8_t> iter_g(*point_cloud, "g");
sensor_msgs::PointCloud2Iterator<uint8_t> iter_b(*point_cloud, "b");
pcd_modifier.resize(point_count);
const int16_t* point_cloud_buffer = reinterpret_cast<const int16_t*>(pointcloud_image.get_buffer());
const uint8_t* color_buffer = color_image.get_buffer();
for (size_t i = 0; i < point_count; i++, ++iter_x, ++iter_y, ++iter_z, ++iter_r, ++iter_g, ++iter_b)
{
// Z in image frame:
float z = static_cast<float>(point_cloud_buffer[3 * i + 2]);
// Alpha value:
uint8_t a = color_buffer[4 * i + 3];
if (z <= 0.0f || a == 0)
{
*iter_x = *iter_y = *iter_z = std::numeric_limits<float>::quiet_NaN();
*iter_r = *iter_g = *iter_b = 0;
}
else
{
constexpr float kMillimeterToMeter = 1.0 / 1000.0f;
*iter_x = kMillimeterToMeter * static_cast<float>(point_cloud_buffer[3 * i + 0]);
*iter_y = kMillimeterToMeter * static_cast<float>(point_cloud_buffer[3 * i + 1]);
*iter_z = kMillimeterToMeter * z;
*iter_r = color_buffer[4 * i + 2];
*iter_g = color_buffer[4 * i + 1];
*iter_b = color_buffer[4 * i + 0];
}
}
return K4A_RESULT_SUCCEEDED;
}
k4a_result_t K4AROSDevice::fillPointCloud(const k4a::image& pointcloud_image, sensor_msgs::PointCloud2Ptr& point_cloud)
{
point_cloud->height = pointcloud_image.get_height_pixels();
point_cloud->width = pointcloud_image.get_width_pixels();
point_cloud->is_dense = false;
point_cloud->is_bigendian = false;
const size_t point_count = pointcloud_image.get_height_pixels() * pointcloud_image.get_width_pixels();
sensor_msgs::PointCloud2Modifier pcd_modifier(*point_cloud);
pcd_modifier.setPointCloud2FieldsByString(1, "xyz");
sensor_msgs::PointCloud2Iterator<float> iter_x(*point_cloud, "x");
sensor_msgs::PointCloud2Iterator<float> iter_y(*point_cloud, "y");
sensor_msgs::PointCloud2Iterator<float> iter_z(*point_cloud, "z");
pcd_modifier.resize(point_count);
const int16_t* point_cloud_buffer = reinterpret_cast<const int16_t*>(pointcloud_image.get_buffer());
for (size_t i = 0; i < point_count; i++, ++iter_x, ++iter_y, ++iter_z)
{
float z = static_cast<float>(point_cloud_buffer[3 * i + 2]);
if (z <= 0.0f)
{
*iter_x = *iter_y = *iter_z = std::numeric_limits<float>::quiet_NaN();
}
else
{
constexpr float kMillimeterToMeter = 1.0 / 1000.0f;
*iter_x = kMillimeterToMeter * static_cast<float>(point_cloud_buffer[3 * i + 0]);
*iter_y = kMillimeterToMeter * static_cast<float>(point_cloud_buffer[3 * i + 1]);
*iter_z = kMillimeterToMeter * z;
}
}
return K4A_RESULT_SUCCEEDED;
}
k4a_result_t K4AROSDevice::getImuFrame(const k4a_imu_sample_t& sample, sensor_msgs::ImuPtr& imu_msg)
{
imu_msg->header.frame_id = calibration_data_.tf_prefix_ + calibration_data_.imu_frame_;
imu_msg->header.stamp = timestampToROS(sample.acc_timestamp_usec);
// The correct convention in ROS is to publish the raw sensor data, in the
// sensor coordinate frame. Do that here.
imu_msg->angular_velocity.x = sample.gyro_sample.xyz.x;
imu_msg->angular_velocity.y = sample.gyro_sample.xyz.y;
imu_msg->angular_velocity.z = sample.gyro_sample.xyz.z;
imu_msg->linear_acceleration.x = sample.acc_sample.xyz.x;
imu_msg->linear_acceleration.y = sample.acc_sample.xyz.y;
imu_msg->linear_acceleration.z = sample.acc_sample.xyz.z;
// Disable the orientation component of the IMU message since it's invalid
imu_msg->orientation_covariance[0] = -1.0;
return K4A_RESULT_SUCCEEDED;
}
#if defined(K4A_BODY_TRACKING)
k4a_result_t K4AROSDevice::getBodyMarker(const k4abt_body_t& body, MarkerPtr marker_msg, int jointType,
ros::Time capture_time)
{
k4a_float3_t position = body.skeleton.joints[jointType].position;
k4a_quaternion_t orientation = body.skeleton.joints[jointType].orientation;
marker_msg->header.frame_id = calibration_data_.tf_prefix_ + calibration_data_.depth_camera_frame_;
marker_msg->header.stamp = capture_time;
// Set the lifetime to 0.25 to prevent flickering for even 5fps configurations.
// New markers with the same ID will replace old markers as soon as they arrive.
marker_msg->lifetime = ros::Duration(0.25);
marker_msg->id = body.id * 100 + jointType;
marker_msg->type = Marker::SPHERE;
Color color = BODY_COLOR_PALETTE[body.id % BODY_COLOR_PALETTE.size()];
marker_msg->color.a = color.a;
marker_msg->color.r = color.r;
marker_msg->color.g = color.g;
marker_msg->color.b = color.b;
marker_msg->scale.x = 0.05;
marker_msg->scale.y = 0.05;
marker_msg->scale.z = 0.05;
marker_msg->pose.position.x = position.v[0] / 1000.0f;
marker_msg->pose.position.y = position.v[1] / 1000.0f;
marker_msg->pose.position.z = position.v[2] / 1000.0f;
marker_msg->pose.orientation.w = orientation.wxyz.w;
marker_msg->pose.orientation.x = orientation.wxyz.x;
marker_msg->pose.orientation.y = orientation.wxyz.y;
marker_msg->pose.orientation.z = orientation.wxyz.z;
return K4A_RESULT_SUCCEEDED;
}
k4a_result_t K4AROSDevice::getBodyIndexMap(const k4abt::frame& body_frame, sensor_msgs::ImagePtr body_index_map_image)
{
k4a::image k4a_body_index_map = body_frame.get_body_index_map();
if (!k4a_body_index_map)
{
ROS_ERROR("Cannot render body index map: no body index map");
return K4A_RESULT_FAILED;
}
return renderBodyIndexMapToROS(body_index_map_image, k4a_body_index_map, body_frame);
}
k4a_result_t K4AROSDevice::renderBodyIndexMapToROS(sensor_msgs::ImagePtr body_index_map_image,
k4a::image& k4a_body_index_map, const k4abt::frame& body_frame)
{
// Access the body index map as an array of uint8 pixels
BodyIndexMapPixel* body_index_map_frame_buffer = k4a_body_index_map.get_buffer();
auto body_index_map_pixel_count = k4a_body_index_map.get_size() / sizeof(BodyIndexMapPixel);
// Build the ROS message
body_index_map_image->height = k4a_body_index_map.get_height_pixels();
body_index_map_image->width = k4a_body_index_map.get_width_pixels();
body_index_map_image->encoding = sensor_msgs::image_encodings::MONO8;
body_index_map_image->is_bigendian = false;
body_index_map_image->step = k4a_body_index_map.get_width_pixels() * sizeof(BodyIndexMapPixel);
// Enlarge the data buffer in the ROS message to hold the frame
body_index_map_image->data.resize(body_index_map_image->height * body_index_map_image->step);
// If the pixel doesn't belong to a detected body the pixels value will be 255 (K4ABT_BODY_INDEX_MAP_BACKGROUND).
// If the pixel belongs to a detected body the value is calculated by body id mod 255.
// This means that up to body id 254 the value is equals the body id.
// Afterwards it will lose the relation to the body id and is only a information for the segmentation of the image.
for (size_t i = 0; i < body_index_map_pixel_count; ++i)
{
BodyIndexMapPixel val = body_index_map_frame_buffer[i];
if (val == K4ABT_BODY_INDEX_MAP_BACKGROUND)
{
body_index_map_image->data[i] = K4ABT_BODY_INDEX_MAP_BACKGROUND;
}
else
{
auto body_id = k4abt_frame_get_body_id(body_frame.handle(), val);
body_index_map_image->data[i] = body_id % K4ABT_BODY_INDEX_MAP_BACKGROUND;
}
}
return K4A_RESULT_SUCCEEDED;
}
#endif
void K4AROSDevice::framePublisherThread()
{
ros::Rate loop_rate(params_.fps);
k4a_wait_result_t wait_result;
k4a_result_t result;
CameraInfo rgb_raw_camera_info;
CameraInfo depth_raw_camera_info;
CameraInfo rgb_rect_camera_info;
CameraInfo depth_rect_camera_info;
CameraInfo ir_raw_camera_info;
Time capture_time;
k4a::capture capture;
if (ci_mngr_rgb_->isCalibrated())
{
rgb_raw_camera_info = depth_rect_camera_info = ci_mngr_rgb_->getCameraInfo();
}
else
{
calibration_data_.getRgbCameraInfo(rgb_raw_camera_info);
calibration_data_.getRgbCameraInfo(depth_rect_camera_info);
}
if (ci_mngr_ir_->isCalibrated())
{
depth_raw_camera_info = rgb_rect_camera_info = ir_raw_camera_info = ci_mngr_ir_->getCameraInfo();
}
else
{
calibration_data_.getDepthCameraInfo(depth_raw_camera_info);
calibration_data_.getDepthCameraInfo(rgb_rect_camera_info);
calibration_data_.getDepthCameraInfo(ir_raw_camera_info);
}
//First frame needs longer to arrive, we wait up to 4 seconds for it
const std::chrono::milliseconds firstFrameWaitTime = std::chrono::milliseconds(4 * 1000);
//fail if we did non receive 5 consecutive frames in a row
const std::chrono::milliseconds regularFrameWaitTime = std::chrono::milliseconds(1000 * 5 / params_.fps);
std::chrono::milliseconds waitTime = firstFrameWaitTime;
while (running_ && ros::ok() && !ros::isShuttingDown())
{
if (k4a_device_)
{
if (!k4a_device_.get_capture(&capture, waitTime))
{
ROS_FATAL("Failed to poll cameras: node cannot continue.");
ros::requestShutdown();
return;
}
else
{
if (params_.depth_enabled)
{
// Update the timestamp offset based on the difference between the system timestamp (i.e., arrival at USB bus)
// and device timestamp (i.e., hardware clock at exposure start).
updateTimestampOffset(capture.get_ir_image().get_device_timestamp(),
capture.get_ir_image().get_system_timestamp());
}
else if (params_.color_enabled)
{
updateTimestampOffset(capture.get_color_image().get_device_timestamp(),
capture.get_color_image().get_system_timestamp());
}
}
waitTime = regularFrameWaitTime;
}
else if (k4a_playback_handle_)
{
std::lock_guard<std::mutex> guard(k4a_playback_handle_mutex_);
if (!k4a_playback_handle_.get_next_capture(&capture))
{
// rewind recording if looping is enabled
if (params_.recording_loop_enabled)
{
k4a_playback_handle_.seek_timestamp(std::chrono::microseconds(0), K4A_PLAYBACK_SEEK_BEGIN);
k4a_playback_handle_.get_next_capture(&capture);
imu_stream_end_of_file_ = false;
last_imu_time_usec_ = 0;
}
else
{
ROS_INFO("Recording reached end of file. node cannot continue.");
ros::requestShutdown();
return;
}
}
last_capture_time_usec_ = getCaptureTimestamp(capture).count();
}
CompressedImagePtr rgb_jpeg_frame(new CompressedImage);
ImagePtr rgb_raw_frame(new Image);
ImagePtr rgb_rect_frame(new Image);
ImagePtr depth_raw_frame(new Image);
ImagePtr depth_rect_frame(new Image);
ImagePtr ir_raw_frame(new Image);
PointCloud2Ptr point_cloud(new PointCloud2);
if (params_.depth_enabled)
{
// Only do compute if we have subscribers
// Only create ir frame when we are using a device or we have an ir image.
// Recordings may not have synchronized captures. For unsynchronized captures without ir image skip ir frame.
if ((ir_raw_publisher_.getNumSubscribers() > 0 || ir_raw_camerainfo_publisher_.getNumSubscribers() > 0) &&
(k4a_device_ || capture.get_ir_image() != nullptr))
{
// IR images are available in all depth modes
result = getIrFrame(capture, ir_raw_frame);
if (result != K4A_RESULT_SUCCEEDED)
{
ROS_ERROR_STREAM("Failed to get raw IR frame");
ros::shutdown();
return;
}
else if (result == K4A_RESULT_SUCCEEDED)
{
capture_time = timestampToROS(capture.get_ir_image().get_device_timestamp());
// Re-sychronize the timestamps with the capture timestamp