Go to the documentation of this file.
   42 #ifndef VELODYNE_POINTCLOUD_RAWDATA_H 
   43 #define VELODYNE_POINTCLOUD_RAWDATA_H 
   48 #include <boost/format.hpp> 
   53 #include <velodyne_msgs/VelodyneScan.h> 
  185   int setupOffline(std::string calibration_file, std::string model, 
double max_range_, 
 
  191   void setParameters(
double min_range, 
double max_range, 
double view_direction, 
double view_width);
 
  250 #endif  // VELODYNE_POINTCLOUD_RAWDATA_H 
  
static const int SCANS_PER_BLOCK
static const uint16_t ROTATION_MAX_UNITS
static const float VLP16_BLOCK_TDURATION
bool pointInRange(float range)
static const int VLP16_FIRINGS_PER_BLOCK
static const int BLOCKS_PER_PACKET
raw_block_t blocks[BLOCKS_PER_PACKET]
static const float VLS128_TOH_ADJUSTMENT
double min_range
minimum range to publish
static const uint16_t VLS128_BANK_1
Calibration information for the entire device.
static const uint16_t UPPER_BANK
static const float VLP16_DSR_TOFFSET
int min_angle
minimum angle to publish
bool buildTimings()
setup per-point timing offsets
void unpack(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data, const ros::Time &scan_start_time)
convert raw packet to point cloud
float sin_rot_table_[ROTATION_MAX_UNITS]
static const uint16_t VLS128_BANK_4
static const float VLS128_MODEL_ID
struct velodyne_rawdata::raw_block raw_block_t
Raw Velodyne data block.
boost::optional< velodyne_pointcloud::Calibration > setup(ros::NodeHandle private_nh)
Set up for data processing.
static const float VLS128_CHANNEL_TDURATION
uint16_t header
UPPER_BANK or LOWER_BANK.
int setupOffline(std::string calibration_file, std::string model, double max_range_, double min_range_)
Set up for data processing offline. Performs the same initialization as in setup, in the abscence of ...
static const int PACKET_STATUS_SIZE
struct velodyne_rawdata::raw_packet raw_packet_t
Raw Velodyne packet.
velodyne_pointcloud::Calibration calibration_
int max_angle
maximum angle to publish
float vls_128_laser_azimuth_cache[16]
void unpack_vls128(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data, const ros::Time &scan_start_time)
convert raw VLS128 packet to point cloud
static const float ROTATION_RESOLUTION
uint8_t status[PACKET_STATUS_SIZE]
float cos_rot_table_[ROTATION_MAX_UNITS]
static const float VLS128_DISTANCE_RESOLUTION
static const float VLP16_FIRING_TOFFSET
Velodyne data conversion class.
std::vector< std::vector< float > > timing_offsets
static const uint16_t VLS128_BANK_2
void setParameters(double min_range, double max_range, double view_direction, double view_width)
uint8_t data[BLOCK_DATA_SIZE]
static const int VLP16_SCANS_PER_FIRING
void unpack_vlp16(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data, const ros::Time &scan_start_time)
convert raw VLP16 packet to point cloud
static const int SCANS_PER_PACKET
static const int RAW_SCAN_SIZE
static const int SIZE_BLOCK
static const float VLS128_SEQ_TDURATION
static const uint16_t LOWER_BANK
int scansPerPacket() const
uint16_t rotation
0-35999, divide by 100 to get degrees
static const int BLOCK_DATA_SIZE
static const int PACKET_SIZE
std::string calibrationFile
calibration file name
static const uint16_t VLS128_BANK_3
double max_range
maximum range to publish
velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Fri Aug 2 2024 08:46:25