Classes | Public Member Functions | Public Attributes | Protected Attributes | List of all members
velodyne_rawdata::DataContainerBase Class Referenceabstract

#include <datacontainerbase.h>

Inheritance diagram for velodyne_rawdata::DataContainerBase:
Inheritance graph
[legend]

Classes

struct  Config
 

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)=0
 
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 ()
 
virtual void newLine ()=0
 
bool pointInRange (float range)
 
virtual void setup (const velodyne_msgs::VelodyneScan::ConstPtr &scan_msg)
 
void transformPoint (float &x, float &y, float &z)
 

Public Attributes

sensor_msgs::PointCloud2 cloud
 

Protected Attributes

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 47 of file datacontainerbase.h.

Constructor & Destructor Documentation

◆ DataContainerBase()

velodyne_rawdata::DataContainerBase::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,
  ... 
)
inline

Definition at line 50 of file datacontainerbase.h.

Member Function Documentation

◆ addPoint()

virtual void velodyne_rawdata::DataContainerBase::addPoint ( float  x,
float  y,
float  z,
const uint16_t  ring,
const uint16_t  azimuth,
const float  distance,
const float  intensity,
const float  time 
)
pure virtual

◆ calculateTransformMatrix()

bool velodyne_rawdata::DataContainerBase::calculateTransformMatrix ( Eigen::Affine3f &  matrix,
const std::string &  target_frame,
const std::string &  source_frame,
const ros::Time time 
)
inline

Definition at line 187 of file datacontainerbase.h.

◆ computeTransformToFixed()

bool velodyne_rawdata::DataContainerBase::computeTransformToFixed ( const ros::Time packet_time)
inline

Definition at line 233 of file datacontainerbase.h.

◆ computeTransformToTarget()

bool velodyne_rawdata::DataContainerBase::computeTransformToTarget ( const ros::Time scan_time)
inline

Definition at line 222 of file datacontainerbase.h.

◆ configure()

void velodyne_rawdata::DataContainerBase::configure ( const double  max_range,
const double  min_range,
const std::string  fixed_frame,
const std::string  target_frame 
)
inline

Definition at line 174 of file datacontainerbase.h.

◆ finishCloud()

const sensor_msgs::PointCloud2& velodyne_rawdata::DataContainerBase::finishCloud ( )
inline

Definition at line 119 of file datacontainerbase.h.

◆ manage_tf_buffer()

void velodyne_rawdata::DataContainerBase::manage_tf_buffer ( )
inline

Definition at line 142 of file datacontainerbase.h.

◆ newLine()

virtual void velodyne_rawdata::DataContainerBase::newLine ( )
pure virtual

◆ pointInRange()

bool velodyne_rawdata::DataContainerBase::pointInRange ( float  range)
inline

Definition at line 260 of file datacontainerbase.h.

◆ setup()

virtual void velodyne_rawdata::DataContainerBase::setup ( const velodyne_msgs::VelodyneScan::ConstPtr &  scan_msg)
inlinevirtual

◆ transformPoint()

void velodyne_rawdata::DataContainerBase::transformPoint ( float &  x,
float &  y,
float &  z 
)
inline

Definition at line 244 of file datacontainerbase.h.

Member Data Documentation

◆ cloud

sensor_msgs::PointCloud2 velodyne_rawdata::DataContainerBase::cloud

Definition at line 185 of file datacontainerbase.h.

◆ config_

Config velodyne_rawdata::DataContainerBase::config_
protected

Definition at line 266 of file datacontainerbase.h.

◆ sensor_frame

std::string velodyne_rawdata::DataContainerBase::sensor_frame
protected

Definition at line 271 of file datacontainerbase.h.

◆ tf_buffer

std::shared_ptr<tf2_ros::Buffer> velodyne_rawdata::DataContainerBase::tf_buffer
protected

Definition at line 268 of file datacontainerbase.h.

◆ tf_listener

std::shared_ptr<tf2_ros::TransformListener> velodyne_rawdata::DataContainerBase::tf_listener
protected

Definition at line 267 of file datacontainerbase.h.

◆ tf_matrix_to_fixed

Eigen::Affine3f velodyne_rawdata::DataContainerBase::tf_matrix_to_fixed
protected

Definition at line 269 of file datacontainerbase.h.

◆ tf_matrix_to_target

Eigen::Affine3f velodyne_rawdata::DataContainerBase::tf_matrix_to_target
protected

Definition at line 270 of file datacontainerbase.h.


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


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