diff --git a/src/cuda_depth_to_lidar.cc b/src/cuda_depth_to_lidar.cc index 906627d..7f73f43 100644 --- a/src/cuda_depth_to_lidar.cc +++ b/src/cuda_depth_to_lidar.cc @@ -360,13 +360,13 @@ class DepthToLidar : public K4AWrapper { } if (depth_image == nullptr) return; - PublishScan(stamp_time); if (FLAGS_depth) { PublishDepthImage(depth_image, stamp_time); } if (FLAGS_points) { DepthToPointCloud(color_image, depth_image); PublishPointCloud(stamp_time); + PublishScan(stamp_time); } } diff --git a/src/depth_to_lidar.cc b/src/depth_to_lidar.cc index 9f615ac..cf10741 100644 --- a/src/depth_to_lidar.cc +++ b/src/depth_to_lidar.cc @@ -370,7 +370,6 @@ class DepthToLidar : public K4AWrapper { } if (depth_image == nullptr) return; - PublishScan(stamp_time); if (FLAGS_depth) { // TODO consider publishing camera info also with same timestamp PublishDepthImage(depth_image, stamp_time); @@ -378,6 +377,7 @@ class DepthToLidar : public K4AWrapper { if (FLAGS_points) { DepthToPointCloud(color_image, depth_image); PublishPointCloud(stamp_time); + PublishScan(stamp_time); } }