42 #ifndef VELODYNE_POINTCLOUD_RAWDATA_H 43 #define VELODYNE_POINTCLOUD_RAWDATA_H 48 #include <boost/format.hpp> 53 #include <velodyne_msgs/VelodyneScan.h> 165 int setupOffline(std::string calibration_file,
double max_range_,
double min_range_);
170 void setParameters(
double min_range,
double max_range,
double view_direction,
double view_width);
172 int scansPerPacket()
const;
210 void unpack_vlp16(
const velodyne_msgs::VelodynePacket& pkt,
DataContainerBase& data,
216 #endif // VELODYNE_POINTCLOUD_RAWDATA_H
static const int PACKET_STATUS_SIZE
std::string calibrationFile
calibration file name
std::vector< std::vector< float > > timing_offsets
static const int SCANS_PER_BLOCK
struct velodyne_rawdata::raw_packet raw_packet_t
Raw Velodyne packet.
Calibration information for the entire device.
static const float ROTATION_RESOLUTION
static const uint16_t UPPER_BANK
static const int RAW_SCAN_SIZE
static const float VLP16_FIRING_TOFFSET
int max_angle
maximum angle to publish
static const uint16_t ROTATION_MAX_UNITS
static const int SIZE_BLOCK
static const int BLOCK_DATA_SIZE
static const uint16_t LOWER_BANK
static const float VLP16_DSR_TOFFSET
uint16_t rotation
0-35999, divide by 100 to get degrees
static const float VLP16_BLOCK_TDURATION
int min_angle
minimum angle to publish
double min_range
minimum range to publish
double max_range
maximum range to publish
static const int BLOCKS_PER_PACKET
static const int VLP16_SCANS_PER_FIRING
struct velodyne_rawdata::raw_block raw_block_t
Raw Velodyne data block.
uint8_t data[BLOCK_DATA_SIZE]
Velodyne data conversion class.
uint16_t header
UPPER_BANK or LOWER_BANK.
static const int PACKET_SIZE
static const int VLP16_FIRINGS_PER_BLOCK
velodyne_pointcloud::Calibration calibration_
static const int SCANS_PER_PACKET