Go to the documentation of this file.
9 const double max_range,
const double min_range,
10 const std::string& target_frame,
const std::string& fixed_frame,
11 const unsigned int scans_per_block)
13 max_range, min_range, target_frame, fixed_frame,
14 0, 1, true, scans_per_block, 6,
21 iter_x(cloud,
"x"), iter_y(cloud,
"y"), iter_z(cloud,
"z"),
22 iter_ring(cloud,
"ring"), iter_intensity(cloud,
"intensity"), iter_time(cloud,
"time")
26 DataContainerBase::setup(scan_msg);
sensor_msgs::PointCloud2Iterator< float > iter_intensity
virtual void setup(const velodyne_msgs::VelodyneScan::ConstPtr &scan_msg)
void transformPoint(float &x, float &y, float &z)
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::PointCloud2 cloud
sensor_msgs::PointCloud2Iterator< float > iter_y
bool pointInRange(float range)
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