8       const double max_range, 
const double min_range,
     9       const std::string& target_frame, 
const std::string& fixed_frame,
    10       const unsigned int num_lasers, 
const unsigned int scans_per_block,
    13         max_range, min_range, target_frame, fixed_frame,
    14         num_lasers, 0, false, scans_per_block, tf_ptr, 6,
    21         iter_x(cloud, 
"x"), iter_y(cloud, 
"y"), iter_z(cloud, 
"z"),
    22         iter_intensity(cloud, 
"intensity"), iter_ring(cloud, 
"ring"), iter_time(cloud, 
"time")
    38     DataContainerBase::setup(scan_msg);
    49       const uint16_t ring, 
const uint16_t , 
const float distance, 
const float intensity, 
const float time)
 sensor_msgs::PointCloud2Iterator< float > iter_time
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_intensity
virtual void setup(const velodyne_msgs::VelodyneScan::ConstPtr &scan_msg)
sensor_msgs::PointCloud2Iterator< float > iter_x
bool pointInRange(float range)
void transformPoint(float &x, float &y, float &z)
sensor_msgs::PointCloud2Iterator< float > iter_z
bool transform
enable / disable transform points 
sensor_msgs::PointCloud2Iterator< float > iter_y
sensor_msgs::PointCloud2Iterator< uint16_t > iter_ring
OrganizedCloudXYZIR(const double max_range, const double min_range, const std::string &target_frame, const std::string &fixed_frame, const unsigned int num_lasers, const unsigned int scans_per_block, boost::shared_ptr< tf::TransformListener > tf_ptr=boost::shared_ptr< tf::TransformListener >())
sensor_msgs::PointCloud2 cloud