Classes | Public Member Functions | Public Attributes | Protected Attributes
velodyne_rawdata::DataContainerBase Class Reference

#include <datacontainerbase.h>

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

List of all members.

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)=0
bool computeTransformation (const ros::Time &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, boost::shared_ptr< tf::TransformListener > &tf_ptr, int fields,...)
const sensor_msgs::PointCloud2 & finishCloud ()
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)
void vectorTfToEigen (tf::Vector3 &tf_vec, Eigen::Vector3f &eigen_vec)

Public Attributes

sensor_msgs::PointCloud2 cloud

Protected Attributes

Config config_
boost::shared_ptr
< tf::TransformListener
tf_ptr
 transform listener
Eigen::Affine3f transformation

Detailed Description

Definition at line 45 of file datacontainerbase.h.


Constructor & Destructor Documentation

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,
boost::shared_ptr< tf::TransformListener > &  tf_ptr,
int  fields,
  ... 
) [inline]

Definition at line 48 of file datacontainerbase.h.


Member Function Documentation

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 
) [pure virtual]

Definition at line 160 of file datacontainerbase.h.

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

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

Definition at line 122 of file datacontainerbase.h.

virtual void velodyne_rawdata::DataContainerBase::newLine ( ) [pure virtual]
bool velodyne_rawdata::DataContainerBase::pointInRange ( float  range) [inline]

Definition at line 196 of file datacontainerbase.h.

virtual void velodyne_rawdata::DataContainerBase::setup ( const velodyne_msgs::VelodyneScan::ConstPtr &  scan_msg) [inline, virtual]
void velodyne_rawdata::DataContainerBase::transformPoint ( float &  x,
float &  y,
float &  z 
) [inline]

Definition at line 188 of file datacontainerbase.h.

void velodyne_rawdata::DataContainerBase::vectorTfToEigen ( tf::Vector3 tf_vec,
Eigen::Vector3f &  eigen_vec 
) [inline]

Definition at line 153 of file datacontainerbase.h.


Member Data Documentation

Definition at line 151 of file datacontainerbase.h.

Definition at line 202 of file datacontainerbase.h.

transform listener

Definition at line 203 of file datacontainerbase.h.

Definition at line 204 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 Wed Jul 3 2019 19:32:23