Public Member Functions | Public Attributes | List of all members
velodyne_pointcloud::PointcloudXYZIRT Class Reference

#include <pointcloudXYZIRT.h>

Inheritance diagram for velodyne_pointcloud::PointcloudXYZIRT:
Inheritance graph
[legend]

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, const float time)
 
virtual void newLine ()
 
 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)
 
virtual void setup (const velodyne_msgs::VelodyneScan::ConstPtr &scan_msg)
 
- Public Member Functions inherited from velodyne_rawdata::DataContainerBase
bool calculateTransformMatrix (Eigen::Affine3f &matrix, const std::string &target_frame, const std::string &source_frame, const ros::Time &time)
 
bool computeTransformToFixed (const ros::Time &packet_time)
 
bool computeTransformToTarget (const ros::Time &scan_time)
 
void configure (const double max_range, const double min_range, const std::string fixed_frame, const std::string target_frame)
 
 DataContainerBase (const double max_range, const double min_range, const std::string &target_frame, const std::string &fixed_frame, const unsigned int init_width, const unsigned int init_height, const bool is_dense, const unsigned int scans_per_packet, int fields,...)
 
const sensor_msgs::PointCloud2 & finishCloud ()
 
void manage_tf_buffer ()
 
bool pointInRange (float range)
 
void transformPoint (float &x, float &y, float &z)
 

Public Attributes

sensor_msgs::PointCloud2Iterator< float > iter_intensity
 
sensor_msgs::PointCloud2Iterator< uint16_t > iter_ring
 
sensor_msgs::PointCloud2Iterator< float > iter_time
 
sensor_msgs::PointCloud2Iterator< float > iter_x
 
sensor_msgs::PointCloud2Iterator< float > iter_y
 
sensor_msgs::PointCloud2Iterator< float > iter_z
 
- Public Attributes inherited from velodyne_rawdata::DataContainerBase
sensor_msgs::PointCloud2 cloud
 

Additional Inherited Members

- Protected Attributes inherited from velodyne_rawdata::DataContainerBase
Config config_
 
std::string sensor_frame
 
std::shared_ptr< tf2_ros::Buffertf_buffer
 
std::shared_ptr< tf2_ros::TransformListenertf_listener
 
Eigen::Affine3f tf_matrix_to_fixed
 
Eigen::Affine3f tf_matrix_to_target
 

Detailed Description

Definition at line 41 of file pointcloudXYZIRT.h.

Constructor & Destructor Documentation

◆ PointcloudXYZIRT()

velodyne_pointcloud::PointcloudXYZIRT::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 
)

Definition at line 8 of file pointcloudXYZIRT.cc.

Member Function Documentation

◆ addPoint()

void velodyne_pointcloud::PointcloudXYZIRT::addPoint ( float  x,
float  y,
float  z,
const uint16_t  ring,
const uint16_t  azimuth,
const float  distance,
const float  intensity,
const float  time 
)
virtual

Implements velodyne_rawdata::DataContainerBase.

Definition at line 38 of file pointcloudXYZIRT.cc.

◆ newLine()

void velodyne_pointcloud::PointcloudXYZIRT::newLine ( )
virtual

Implements velodyne_rawdata::DataContainerBase.

Definition at line 35 of file pointcloudXYZIRT.cc.

◆ setup()

void velodyne_pointcloud::PointcloudXYZIRT::setup ( const velodyne_msgs::VelodyneScan::ConstPtr &  scan_msg)
virtual

Reimplemented from velodyne_rawdata::DataContainerBase.

Definition at line 25 of file pointcloudXYZIRT.cc.

Member Data Documentation

◆ iter_intensity

sensor_msgs::PointCloud2Iterator<float> velodyne_pointcloud::PointcloudXYZIRT::iter_intensity

Definition at line 54 of file pointcloudXYZIRT.h.

◆ iter_ring

sensor_msgs::PointCloud2Iterator<uint16_t> velodyne_pointcloud::PointcloudXYZIRT::iter_ring

Definition at line 55 of file pointcloudXYZIRT.h.

◆ iter_time

sensor_msgs::PointCloud2Iterator<float> velodyne_pointcloud::PointcloudXYZIRT::iter_time

Definition at line 54 of file pointcloudXYZIRT.h.

◆ iter_x

sensor_msgs::PointCloud2Iterator<float> velodyne_pointcloud::PointcloudXYZIRT::iter_x

Definition at line 54 of file pointcloudXYZIRT.h.

◆ iter_y

sensor_msgs::PointCloud2Iterator<float> velodyne_pointcloud::PointcloudXYZIRT::iter_y

Definition at line 54 of file pointcloudXYZIRT.h.

◆ iter_z

sensor_msgs::PointCloud2Iterator<float> velodyne_pointcloud::PointcloudXYZIRT::iter_z

Definition at line 54 of file pointcloudXYZIRT.h.


The documentation for this class was generated from the following files:


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Tue May 2 2023 02:28:04