Go to the documentation of this file.
33 #ifndef VELODYNE_POINTCLOUD_POINTCLOUDXYZIRT_H
34 #define VELODYNE_POINTCLOUD_POINTCLOUDXYZIRT_H
44 PointcloudXYZIRT(
const double max_range,
const double min_range,
const std::string& target_frame,
45 const std::string& fixed_frame,
const unsigned int scans_per_block);
49 virtual void setup(
const velodyne_msgs::VelodyneScan::ConstPtr& scan_msg);
51 virtual void addPoint(
float x,
float y,
float z,
const uint16_t ring,
const uint16_t azimuth,
52 const float distance,
const float intensity,
const float time);
59 #endif // VELODYNE_POINTCLOUD_POINTCLOUDXYZIRT_H
sensor_msgs::PointCloud2Iterator< float > iter_intensity
virtual void setup(const velodyne_msgs::VelodyneScan::ConstPtr &scan_msg)
virtual void addPoint(float x, float y, float z, const uint16_t ring, const uint16_t azimuth, const float distance, const float intensity, const float time)
sensor_msgs::PointCloud2Iterator< float > iter_y
PointcloudXYZIRT(const double max_range, const double min_range, const std::string &target_frame, const std::string &fixed_frame, const unsigned int scans_per_block)
sensor_msgs::PointCloud2Iterator< uint16_t > iter_ring
sensor_msgs::PointCloud2Iterator< float > iter_z
sensor_msgs::PointCloud2Iterator< float > iter_x
sensor_msgs::PointCloud2Iterator< float > iter_time
velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Sun Jun 2 2024 02:29:13