#include <organized_cloudXYZIR.h>
Public Member Functions | |
virtual void | addPoint (float x, float y, float z, const uint16_t ring, const uint16_t azimuth, const float distance, const float intensity) |
virtual void | newLine () |
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 >()) | |
virtual void | setup (const velodyne_msgs::VelodyneScan::ConstPtr &scan_msg) |
Private Attributes | |
sensor_msgs::PointCloud2Iterator < float > | iter_intensity |
sensor_msgs::PointCloud2Iterator < uint16_t > | iter_ring |
sensor_msgs::PointCloud2Iterator < float > | iter_x |
sensor_msgs::PointCloud2Iterator < float > | iter_y |
sensor_msgs::PointCloud2Iterator < float > | iter_z |
Definition at line 42 of file organized_cloudXYZIR.h.
velodyne_pointcloud::OrganizedCloudXYZIR::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>() |
||
) |
Definition at line 7 of file organized_cloudXYZIR.cc.
void velodyne_pointcloud::OrganizedCloudXYZIR::addPoint | ( | float | x, |
float | y, | ||
float | z, | ||
const uint16_t | ring, | ||
const uint16_t | azimuth, | ||
const float | distance, | ||
const float | intensity | ||
) | [virtual] |
The laser values are not ordered, the organized structure needs ordered neighbour points. The right order is defined by the laser_ring value. To keep the right ordering, the filtered values are set to NaN.
Implements velodyne_rawdata::DataContainerBase.
Definition at line 45 of file organized_cloudXYZIR.cc.
void velodyne_pointcloud::OrganizedCloudXYZIR::newLine | ( | ) | [virtual] |
Implements velodyne_rawdata::DataContainerBase.
Definition at line 25 of file organized_cloudXYZIR.cc.
void velodyne_pointcloud::OrganizedCloudXYZIR::setup | ( | const velodyne_msgs::VelodyneScan::ConstPtr & | scan_msg | ) | [virtual] |
Reimplemented from velodyne_rawdata::DataContainerBase.
Definition at line 35 of file organized_cloudXYZIR.cc.
sensor_msgs::PointCloud2Iterator<float> velodyne_pointcloud::OrganizedCloudXYZIR::iter_intensity [private] |
Definition at line 57 of file organized_cloudXYZIR.h.
sensor_msgs::PointCloud2Iterator<uint16_t> velodyne_pointcloud::OrganizedCloudXYZIR::iter_ring [private] |
Definition at line 58 of file organized_cloudXYZIR.h.
Definition at line 57 of file organized_cloudXYZIR.h.
Definition at line 57 of file organized_cloudXYZIR.h.
Definition at line 57 of file organized_cloudXYZIR.h.