diff --git a/pcl_ros/include/pcl_ros/point_cloud.h b/pcl_ros/include/pcl_ros/point_cloud.h index 03c925de..167537ee 100644 --- a/pcl_ros/include/pcl_ros/point_cloud.h +++ b/pcl_ros/include/pcl_ros/point_cloud.h @@ -213,8 +213,8 @@ namespace ros inline static void read(Stream& stream, pcl::PointCloud& m) { std_msgs::Header header; - pcl_conversions::fromPCL(m.header, header); stream.next(header); + pcl_conversions::toPCL(header, m.header); stream.next(m.height); stream.next(m.width);