36 #ifndef INDIGO_PCL_CONVERSIONS_H__ 37 #define INDIGO_PCL_CONVERSIONS_H__ 43 #include <pcl/conversions.h> 45 #include <pcl/PCLHeader.h> 46 #include <std_msgs/Header.h> 48 #include <pcl/PCLImage.h> 49 #include <sensor_msgs/Image.h> 51 #include <pcl/PCLPointField.h> 52 #include <sensor_msgs/PointField.h> 54 #include <pcl/PCLPointCloud2.h> 55 #include <sensor_msgs/PointCloud2.h> 57 #include <pcl/PointIndices.h> 58 #include <pcl_msgs/PointIndices.h> 60 #include <pcl/ModelCoefficients.h> 61 #include <pcl_msgs/ModelCoefficients.h> 63 #include <pcl/Vertices.h> 64 #include <pcl_msgs/Vertices.h> 66 #include <pcl/PolygonMesh.h> 67 #include <pcl_msgs/PolygonMesh.h> 69 #include <pcl/io/pcd_io.h> 71 #include <Eigen/StdVector> 72 #include <Eigen/Geometry> 87 pcl_stamp = stamp.
toNSec() / 1e3;
101 pcl::uint64_t pcl_stamp;
102 toPCL(stamp, pcl_stamp);
Time & fromNSec(uint64_t t)
void fromPCL(const pcl::uint64_t &pcl_stamp, ros::Time &stamp)
void toPCL(const ros::Time &stamp, pcl::uint64_t &pcl_stamp)