diff --git a/AutowareAuto/src/perception/filters/point_cloud_fusion_nodes/src/point_cloud_fusion_node.cpp b/AutowareAuto/src/perception/filters/point_cloud_fusion_nodes/src/point_cloud_fusion_node.cpp index 65c6c6a5..4021f4ee 100644 --- a/AutowareAuto/src/perception/filters/point_cloud_fusion_nodes/src/point_cloud_fusion_node.cpp +++ b/AutowareAuto/src/perception/filters/point_cloud_fusion_nodes/src/point_cloud_fusion_node.cpp @@ -57,8 +57,8 @@ void PointCloudFusionNode::init() m_cloud_capacity, m_input_topics.size()); - using autoware::common::types::PointXYZI; - point_cloud_msg_wrapper::PointCloud2Modifier{ + using autoware::common::types::PointXYZIF; + point_cloud_msg_wrapper::PointCloud2Modifier{ m_cloud_concatenated, m_output_frame_id}.reserve(m_cloud_capacity); if (m_input_topics.size() > 8 || m_input_topics.size() < 2) { @@ -104,8 +104,8 @@ PointCloudFusionNode::pointcloud_callback( msg8}; // reset pointcloud before using - using autoware::common::types::PointXYZI; - point_cloud_msg_wrapper::PointCloud2Modifier modifier{m_cloud_concatenated}; + using autoware::common::types::PointXYZIF; + point_cloud_msg_wrapper::PointCloud2Modifier modifier{m_cloud_concatenated}; modifier.clear(); modifier.reserve(m_cloud_capacity);