#include <organized_cloudXYZIR.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) |
|
virtual void | newLine () |
|
| OrganizedCloudXYZIR (const double max_range, const double min_range, const std::string &target_frame, const std::string &fixed_frame, const unsigned int num_lasers, const unsigned int scans_per_block, boost::shared_ptr< tf::TransformListener > tf_ptr=boost::shared_ptr< tf::TransformListener >()) |
|
virtual void | setup (const velodyne_msgs::VelodyneScan::ConstPtr &scan_msg) |
|
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 () |
|
bool | pointInRange (float range) |
|
void | transformPoint (float &x, float &y, float &z) |
|
void | vectorTfToEigen (tf::Vector3 &tf_vec, Eigen::Vector3f &eigen_vec) |
|
Definition at line 42 of file organized_cloudXYZIR.h.
void velodyne_pointcloud::OrganizedCloudXYZIR::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 |
The laser values are not ordered, the organized structure needs ordered neighbour points. The right order is defined by the laser_ring value. To keep the right ordering, the filtered values are set to NaN.
Implements velodyne_rawdata::DataContainerBase.
Definition at line 48 of file organized_cloudXYZIR.cc.
void velodyne_pointcloud::OrganizedCloudXYZIR::newLine |
( |
| ) |
|
|
virtual |
void velodyne_pointcloud::OrganizedCloudXYZIR::setup |
( |
const velodyne_msgs::VelodyneScan::ConstPtr & |
scan_msg | ) |
|
|
virtual |
The documentation for this class was generated from the following files: