#include <pointcloudXYZIR.h>
Public Member Functions | |
virtual void | addPoint (float x, float y, float z, uint16_t ring, uint16_t azimuth, float distance, float intensity) |
virtual void | newLine () |
PointcloudXYZIR (const double max_range, const double min_range, const std::string &target_frame, const std::string &fixed_frame, 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) |
Public 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 41 of file pointcloudXYZIR.h.
velodyne_pointcloud::PointcloudXYZIR::PointcloudXYZIR | ( | const double | max_range, |
const double | min_range, | ||
const std::string & | target_frame, | ||
const std::string & | fixed_frame, | ||
const unsigned int | scans_per_block, | ||
boost::shared_ptr< tf::TransformListener > | tf_ptr = boost::shared_ptr<tf::TransformListener>() |
||
) |
Definition at line 9 of file pointcloudXYZIR.cc.
void velodyne_pointcloud::PointcloudXYZIR::addPoint | ( | float | x, |
float | y, | ||
float | z, | ||
uint16_t | ring, | ||
uint16_t | azimuth, | ||
float | distance, | ||
float | intensity | ||
) | [virtual] |
Implements velodyne_rawdata::DataContainerBase.
Definition at line 37 of file pointcloudXYZIR.cc.
void velodyne_pointcloud::PointcloudXYZIR::newLine | ( | ) | [virtual] |
Implements velodyne_rawdata::DataContainerBase.
Definition at line 34 of file pointcloudXYZIR.cc.
void velodyne_pointcloud::PointcloudXYZIR::setup | ( | const velodyne_msgs::VelodyneScan::ConstPtr & | scan_msg | ) | [virtual] |
Reimplemented from velodyne_rawdata::DataContainerBase.
Definition at line 25 of file pointcloudXYZIR.cc.
Definition at line 54 of file pointcloudXYZIR.h.
Definition at line 55 of file pointcloudXYZIR.h.
Definition at line 54 of file pointcloudXYZIR.h.
Definition at line 54 of file pointcloudXYZIR.h.
Definition at line 54 of file pointcloudXYZIR.h.