diff --git a/sensing/radar_scan_to_pointcloud2/src/radar_scan_to_pointcloud2_node/radar_scan_to_pointcloud2_node.cpp b/sensing/radar_scan_to_pointcloud2/src/radar_scan_to_pointcloud2_node/radar_scan_to_pointcloud2_node.cpp index 039f31fe10ba6..70b377f0dc405 100644 --- a/sensing/radar_scan_to_pointcloud2/src/radar_scan_to_pointcloud2_node/radar_scan_to_pointcloud2_node.cpp +++ b/sensing/radar_scan_to_pointcloud2/src/radar_scan_to_pointcloud2_node/radar_scan_to_pointcloud2_node.cpp @@ -42,7 +42,8 @@ pcl::PointXYZI getPointXYZI(const radar_msgs::msg::RadarReturn & radar, float in const float x = r_xy * std::cos(radar.azimuth); const float y = r_xy * std::sin(radar.azimuth); const float z = radar.range * std::sin(radar.elevation); - return pcl::PointXYZI{x, y, z, intensity}; + pcl::PointXYZI point{x, y, z, intensity}; + return point; } pcl::PointCloud toAmplitudePCL(const radar_msgs::msg::RadarScan & radar_scan)