Velodyne data conversion class. More...
#include <rawdata.h>
Classes | |
struct | Config |
Public Member Functions | |
RawData () | |
void | setParameters (double min_range, double max_range, double view_direction, double view_width) |
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) |
void | unpack_vlp16 (const velodyne_msgs::VelodynePacket &pkt, VPointCloud &pc) |
convert raw VLP16 packet to point cloud | |
Private Attributes | |
velodyne_pointcloud::Calibration | calibration_ |
Config | config_ |
float | cos_rot_table_ [ROTATION_MAX_UNITS] |
float | sin_rot_table_ [ROTATION_MAX_UNITS] |
Definition at line 45 of file rawdata.cc.
velodyne_rawdata::RawData::~RawData | ( | ) | [inline] |
bool velodyne_rawdata::RawData::pointInRange | ( | float | range | ) | [inline, private] |
void velodyne_rawdata::RawData::setParameters | ( | double | min_range, |
double | max_range, | ||
double | view_direction, | ||
double | view_width | ||
) |
Uppdate parameters: conversions and update
Definition at line 48 of file rawdata.cc.
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 77 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) |
special parsing for the VLP16
< hardware laser number
Position Calculation
the new term of 'vert_offset * sin_vert_angle' was added to the expression due to the mathemathical model we used.
the new term of 'vert_offset * sin_vert_angle' was added to the expression due to the mathemathical model we used.
the expression wiht '-' is proved to be better than the one with '+'
the new term of 'vert_offset * sin_vert_angle' was added to the expression due to the mathemathical model we used.
the new term of 'vert_offset * cos_vert_angle' was added to the expression due to the mathemathical model we used.
Use standard ROS coordinate system (right-hand rule)
Intensity Calculation
Definition at line 114 of file rawdata.cc.
void velodyne_rawdata::RawData::unpack_vlp16 | ( | const velodyne_msgs::VelodynePacket & | pkt, |
VPointCloud & | pc | ||
) | [private] |
convert raw VLP16 packet to point cloud
add private function to handle the VLP16
pkt | raw packet to unpack |
pc | shared pointer to point cloud (points are appended) |
Position Calculation
correct for the laser rotation as a function of timing during the firings
the new term of 'vert_offset * sin_vert_angle' was added to the expression due to the mathemathical model we used.
the new term of 'vert_offset * sin_vert_angle' was added to the expression due to the mathemathical model we used.
the new term of 'vert_offset * sin_vert_angle' was added to the expression due to the mathemathical model we used.
the new term of 'vert_offset * cos_vert_angle' was added to the expression due to the mathemathical model we used.
Use standard ROS coordinate system (right-hand rule)
Intensity Calculation
Definition at line 283 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] |