33 #ifndef VELODYNE_POINTCLOUD_ORGANIZED_CLOUDXYZIR_H 34 #define VELODYNE_POINTCLOUD_ORGANIZED_CLOUDXYZIR_H 45 OrganizedCloudXYZIR(
const double max_range,
const double min_range,
const std::string& target_frame,
46 const std::string& fixed_frame,
const unsigned int num_lasers,
const unsigned int scans_per_block,
51 virtual void setup(
const velodyne_msgs::VelodyneScan::ConstPtr& scan_msg);
53 virtual void addPoint(
float x,
float y,
float z,
const uint16_t ring,
const uint16_t azimuth,
const float distance,
54 const float intensity);
61 #endif // VELODYNE_POINTCLOUD_ORGANIZED_CLOUDXYZIR_H virtual void addPoint(float x, float y, float z, const uint16_t ring, const uint16_t azimuth, const float distance, const float intensity)
TFSIMD_FORCE_INLINE tfScalar distance(const Vector3 &v) const
TFSIMD_FORCE_INLINE const tfScalar & y() const
sensor_msgs::PointCloud2Iterator< float > iter_intensity
virtual void setup(const velodyne_msgs::VelodyneScan::ConstPtr &scan_msg)
boost::shared_ptr< tf::TransformListener > tf_ptr
transform listener
sensor_msgs::PointCloud2Iterator< float > iter_x
TFSIMD_FORCE_INLINE const tfScalar & x() const
sensor_msgs::PointCloud2Iterator< float > iter_z
TFSIMD_FORCE_INLINE const tfScalar & z() const
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 >())