#include <datacontainerbase.h>
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 |
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] |
Definition at line 48 of file datacontainerbase.h.
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] |
Implemented in velodyne_pointcloud::OrganizedCloudXYZIR, and velodyne_pointcloud::PointcloudXYZIR.
bool velodyne_rawdata::DataContainerBase::computeTransformation | ( | const ros::Time & | time | ) | [inline] |
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] |
Implemented in velodyne_pointcloud::OrganizedCloudXYZIR, and velodyne_pointcloud::PointcloudXYZIR.
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] |
Reimplemented in velodyne_pointcloud::OrganizedCloudXYZIR, and velodyne_pointcloud::PointcloudXYZIR.
Definition at line 109 of file datacontainerbase.h.
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.
sensor_msgs::PointCloud2 velodyne_rawdata::DataContainerBase::cloud |
Definition at line 151 of file datacontainerbase.h.
Config velodyne_rawdata::DataContainerBase::config_ [protected] |
Definition at line 202 of file datacontainerbase.h.
boost::shared_ptr<tf::TransformListener> velodyne_rawdata::DataContainerBase::tf_ptr [protected] |
transform listener
Definition at line 203 of file datacontainerbase.h.
Eigen::Affine3f velodyne_rawdata::DataContainerBase::transformation [protected] |
Definition at line 204 of file datacontainerbase.h.