From 2f2c3c4158e7581e462ac8a5c6265e688fbe8207 Mon Sep 17 00:00:00 2001 From: Ussama Naal Date: Thu, 12 Oct 2023 12:46:08 -0700 Subject: [PATCH] shorten function name --- ouster-ros/src/point_cloud_compose.h | 8 ++------ ouster-ros/src/point_cloud_processor_factory.h | 13 +++++++------ 2 files changed, 9 insertions(+), 12 deletions(-) diff --git a/ouster-ros/src/point_cloud_compose.h b/ouster-ros/src/point_cloud_compose.h index 7e3160c7..4ed3ef23 100644 --- a/ouster-ros/src/point_cloud_compose.h +++ b/ouster-ros/src/point_cloud_compose.h @@ -64,7 +64,7 @@ template using Cloud = pcl::PointCloud; template & PROFILE, typename PointT, typename PointS> -void scan_to_cloud_f_destaggered_tuple( +void scan_to_cloud_f_destaggered( ouster_ros::Cloud& cloud, PointS& staging_point, const ouster::PointsF& points, @@ -72,9 +72,7 @@ void scan_to_cloud_f_destaggered_tuple( const std::vector& pixel_shift_by_row) { auto profile_tuple = compose_tuple_table<0, N, PROFILE>(); - map_scan_fields_to_tuple<0, N, PROFILE>(profile_tuple, ls); - auto timestamp = ls.timestamp(); for (auto u = 0; u < ls.h; u++) { @@ -84,19 +82,17 @@ void scan_to_cloud_f_destaggered_tuple( const auto src_idx = u * ls.w + v_shift; const auto tgt_idx = u * ls.w + v; const auto xyz = points.row(src_idx); - // if target point and staging point has matching type bind the target directly // and avoid performing transform_point at the end auto& pt = CondBinaryBind>::run( cloud.points[tgt_idx], staging_point); - + // all native point types have x, y, z, t and ring values pt.x = static_cast(xyz(0)); pt.y = static_cast(xyz(1)); pt.z = static_cast(xyz(2)); pt.t = static_cast(ts); pt.ring = static_cast(u); tuple_copy_values<0, N, PROFILE>(pt, profile_tuple, src_idx); - // only perform point transform operation when PointT, and PointS don't match CondBinaryOp>::run(cloud.points[tgt_idx], staging_point, [](auto& tgt_pt, const auto& src_pt) { diff --git a/ouster-ros/src/point_cloud_processor_factory.h b/ouster-ros/src/point_cloud_processor_factory.h index f6e9cc4e..faa9bf7c 100644 --- a/ouster-ros/src/point_cloud_processor_factory.h +++ b/ouster-ros/src/point_cloud_processor_factory.h @@ -21,7 +21,7 @@ class PointCloudProcessorFactory { int return_index) { unused_variable(return_index); static Point_LEGACY staging_pt; // TODO: temporary, will remove - scan_to_cloud_f_destaggered_tuple( + scan_to_cloud_f_destaggered( cloud, staging_pt, points, scan_ts, ls, pixel_shift_by_row); }; @@ -33,12 +33,12 @@ class PointCloudProcessorFactory { int return_index) { static Point_RNG19_RFL8_SIG16_NIR16_DUAL staging_pt; // TODO: temporary, will remove if (return_index == 0) { - scan_to_cloud_f_destaggered_tuple< + scan_to_cloud_f_destaggered< Profile_RNG19_RFL8_SIG16_NIR16_DUAL.size(), Profile_RNG19_RFL8_SIG16_NIR16_DUAL>( cloud, staging_pt, points, scan_ts, ls, pixel_shift_by_row); } else { - scan_to_cloud_f_destaggered_tuple< + scan_to_cloud_f_destaggered< Profile_RNG19_RFL8_SIG16_NIR16_DUAL_2ND_RETURN.size(), Profile_RNG19_RFL8_SIG16_NIR16_DUAL_2ND_RETURN>( cloud, staging_pt, points, scan_ts, ls, pixel_shift_by_row); } @@ -52,7 +52,7 @@ class PointCloudProcessorFactory { int return_index) { unused_variable(return_index); static Point_RNG19_RFL8_SIG16_NIR16 staging_pt; // TODO: temporary, will remove - scan_to_cloud_f_destaggered_tuple< + scan_to_cloud_f_destaggered< Profile_RNG19_RFL8_SIG16_NIR16.size(), Profile_RNG19_RFL8_SIG16_NIR16>( cloud, staging_pt, points, scan_ts, ls, pixel_shift_by_row); }; @@ -65,12 +65,13 @@ class PointCloudProcessorFactory { int return_index) { unused_variable(return_index); static Point_RNG15_RFL8_NIR8 staging_pt; // TODO: temporary, will remove - scan_to_cloud_f_destaggered_tuple< + scan_to_cloud_f_destaggered< Profile_RNG15_RFL8_NIR8.size(), Profile_RNG15_RFL8_NIR8>( cloud, staging_pt, points, scan_ts, ls, pixel_shift_by_row); }; default: + // TODO: propagate error message // RCLCPP_WARN_STREAM(get_logger(), // "point_type is set to auto but current udp_profile_lidar is unsupported " // "! falling back to the driver default/legacy pcl point format"); @@ -81,7 +82,7 @@ class PointCloudProcessorFactory { int return_index) { unused_variable(return_index); static Point_LEGACY staging_pt; // TODO: temporary, will remove - scan_to_cloud_f_destaggered_tuple( + scan_to_cloud_f_destaggered( cloud, staging_pt, points, scan_ts, ls, pixel_shift_by_row); }; }