$search
Velodyne data conversion class. More...
#include <rawdata.h>
Classes | |
struct | Config |
Public Member Functions | |
RawData () | |
int | setup (ros::NodeHandle private_nh) |
Set up for data processing. | |
void | unpack (const velodyne_msgs::VelodynePacket &pkt, VPointCloud &pc) |
convert raw packet to point cloud | |
~RawData () | |
Private Member Functions | |
bool | pointInRange (float range) |
Private Attributes | |
velodyne_pointcloud::Calibration | calibration_ |
Config | config_ |
float | cos_rot_table_ [ROTATION_MAX_UNITS] |
float | sin_rot_table_ [ROTATION_MAX_UNITS] |
Velodyne data conversion class.
Definition at line 112 of file rawdata.h.
velodyne_rawdata::RawData::RawData | ( | ) |
Definition at line 44 of file rawdata.cc.
bool velodyne_rawdata::RawData::pointInRange | ( | float | range | ) | [inline, private] |
int velodyne_rawdata::RawData::setup | ( | ros::NodeHandle | private_nh | ) |
Set up for data processing.
Perform initializations needed before data processing can begin:
private_nh | private node handle for ROS parameters |
Set up for on-line operation.
Definition at line 47 of file rawdata.cc.
void velodyne_rawdata::RawData::unpack | ( | const velodyne_msgs::VelodynePacket & | pkt, | |
VPointCloud & | pc | |||
) |
convert raw packet to point cloud
pkt | raw packet to unpack | |
pc | shared pointer to point cloud (points are appended) |
< hardware laser number
Position Calculation
Use standard ROS coordinate system (right-hand rule)
Intensity Calculation
Definition at line 89 of file rawdata.cc.
Config velodyne_rawdata::RawData::config_ [private] |
float velodyne_rawdata::RawData::cos_rot_table_[ROTATION_MAX_UNITS] [private] |
float velodyne_rawdata::RawData::sin_rot_table_[ROTATION_MAX_UNITS] [private] |