#include <datacontainerbase.h>
|
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 | 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) |
|
|
sensor_msgs::PointCloud2 | cloud |
|
Definition at line 45 of file datacontainerbase.h.
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 |
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 |
bool velodyne_rawdata::DataContainerBase::computeTransformation |
( |
const ros::Time & |
time | ) |
|
|
inline |
void velodyne_rawdata::DataContainerBase::configure |
( |
const double |
max_range, |
|
|
const double |
min_range, |
|
|
const std::string |
fixed_frame, |
|
|
const std::string |
target_frame |
|
) |
| |
|
inline |
const sensor_msgs::PointCloud2& velodyne_rawdata::DataContainerBase::finishCloud |
( |
| ) |
|
|
inline |
virtual void velodyne_rawdata::DataContainerBase::newLine |
( |
| ) |
|
|
pure virtual |
bool velodyne_rawdata::DataContainerBase::pointInRange |
( |
float |
range | ) |
|
|
inline |
virtual void velodyne_rawdata::DataContainerBase::setup |
( |
const velodyne_msgs::VelodyneScan::ConstPtr & |
scan_msg | ) |
|
|
inlinevirtual |
void velodyne_rawdata::DataContainerBase::transformPoint |
( |
float & |
x, |
|
|
float & |
y, |
|
|
float & |
z |
|
) |
| |
|
inline |
void velodyne_rawdata::DataContainerBase::vectorTfToEigen |
( |
tf::Vector3 & |
tf_vec, |
|
|
Eigen::Vector3f & |
eigen_vec |
|
) |
| |
|
inline |
sensor_msgs::PointCloud2 velodyne_rawdata::DataContainerBase::cloud |
Config velodyne_rawdata::DataContainerBase::config_ |
|
protected |
Eigen::Affine3f velodyne_rawdata::DataContainerBase::transformation |
|
protected |
The documentation for this class was generated from the following file: