rawdata.h
Go to the documentation of this file.
1 // Copyright (C) 2007, 2009, 2010, 2012, 2019 Yaxin Liu, Patrick Beeson, Jack O'Quin, Joshua Whitley
2 // All rights reserved.
3 //
4 // Software License Agreement (BSD License 2.0)
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions
8 // are met:
9 //
10 // * Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 // * Redistributions in binary form must reproduce the above
13 // copyright notice, this list of conditions and the following
14 // disclaimer in the documentation and/or other materials provided
15 // with the distribution.
16 // * Neither the name of {copyright_holder} nor the names of its
17 // contributors may be used to endorse or promote products derived
18 // from this software without specific prior written permission.
19 //
20 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 // POSSIBILITY OF SUCH DAMAGE.
32 
42 #ifndef VELODYNE_POINTCLOUD_RAWDATA_H
43 #define VELODYNE_POINTCLOUD_RAWDATA_H
44 
45 #include <errno.h>
46 #include <stdint.h>
47 #include <string>
48 #include <boost/format.hpp>
49 #include <math.h>
50 #include <vector>
51 
52 #include <ros/ros.h>
53 #include <velodyne_msgs/VelodyneScan.h>
56 
57 namespace velodyne_rawdata
58 {
62 static const int SIZE_BLOCK = 100;
63 static const int RAW_SCAN_SIZE = 3;
64 static const int SCANS_PER_BLOCK = 32;
66 
67 static const float ROTATION_RESOLUTION = 0.01f; // [deg]
68 static const uint16_t ROTATION_MAX_UNITS = 36000u; // [deg/100]
69 
71 static const uint16_t UPPER_BANK = 0xeeff;
72 static const uint16_t LOWER_BANK = 0xddff;
73 
75 static const int VLP16_FIRINGS_PER_BLOCK = 2;
76 static const int VLP16_SCANS_PER_FIRING = 16;
77 static const float VLP16_BLOCK_TDURATION = 110.592f; // [µs]
78 static const float VLP16_DSR_TOFFSET = 2.304f; // [µs]
79 static const float VLP16_FIRING_TOFFSET = 55.296f; // [µs]
80 
88 typedef struct raw_block
89 {
90  uint16_t header;
91  uint16_t rotation;
93 }
95 
102 {
103  uint16_t uint;
104  uint8_t bytes[2];
105 };
106 
107 static const int PACKET_SIZE = 1206;
108 static const int BLOCKS_PER_PACKET = 12;
109 static const int PACKET_STATUS_SIZE = 4;
111 
113 // These are used to detect which bank of 32 lasers is in this block
114 static const uint16_t VLS128_BANK_1 = 0xeeff;
115 static const uint16_t VLS128_BANK_2 = 0xddff;
116 static const uint16_t VLS128_BANK_3 = 0xccff;
117 static const uint16_t VLS128_BANK_4 = 0xbbff;
118 
119 static const float VLS128_CHANNEL_TDURATION = 2.665f; // [µs] Channels corresponds to one laser firing
120 static const float VLS128_SEQ_TDURATION = 53.3f; // [µs] Sequence is a set of laser firings including recharging
121 static const float VLS128_TOH_ADJUSTMENT = 8.7f; // [µs] μs. Top Of the Hour is aligned with the fourth firing group in a firing sequence.
122 static const float VLS128_DISTANCE_RESOLUTION= 0.004f; // [m]
123 static const float VLS128_MODEL_ID= 161;
124 
125 
126 
139 typedef struct raw_packet
140 {
142  uint16_t revolution;
144 }
146 
148 class RawData
149 {
150 public:
151  RawData();
153  {
154  }
155 
166  boost::optional<velodyne_pointcloud::Calibration> setup(ros::NodeHandle private_nh);
167 
168 
169  void setupSinCosCache();
170  void setupAzimuthCache();
171  bool loadCalibration();
172 
185  int setupOffline(std::string calibration_file, std::string model, double max_range_,
186  double min_range_);
187 
188  void unpack(const velodyne_msgs::VelodynePacket& pkt, DataContainerBase& data,
189  const ros::Time& scan_start_time);
190 
191  void setParameters(double min_range, double max_range, double view_direction, double view_width);
192 
193  int scansPerPacket() const;
194 
195 private:
197  typedef struct
198  {
199  std::string model;
200  std::string calibrationFile;
201  double max_range;
202  double min_range;
203  int min_angle;
204  int max_angle;
205 
208  }
209  Config;
211 
218 
219  // Caches the azimuth percent offset for the VLS-128 laser firings
221 
222  // timing offset lookup table
223  std::vector< std::vector<float> > timing_offsets;
224 
231  bool buildTimings();
232 
234  void unpack_vlp16(const velodyne_msgs::VelodynePacket& pkt, DataContainerBase& data,
235  const ros::Time& scan_start_time);
236 
237  void unpack_vls128(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase& data,
238  const ros::Time& scan_start_time);
239 
241  inline bool pointInRange(float range)
242  {
243  return (range >= config_.min_range
244  && range <= config_.max_range);
245  }
246 };
247 
248 } // namespace velodyne_rawdata
249 
250 #endif // VELODYNE_POINTCLOUD_RAWDATA_H
velodyne_rawdata::RawData::~RawData
~RawData()
Definition: rawdata.h:152
velodyne_rawdata::RawData::Config::tmp_min_angle
double tmp_min_angle
Definition: rawdata.h:206
velodyne_rawdata::SCANS_PER_BLOCK
static const int SCANS_PER_BLOCK
Definition: rawdata.h:64
velodyne_rawdata::ROTATION_MAX_UNITS
static const uint16_t ROTATION_MAX_UNITS
Definition: rawdata.h:68
velodyne_rawdata::VLP16_BLOCK_TDURATION
static const float VLP16_BLOCK_TDURATION
Definition: rawdata.h:77
datacontainerbase.h
velodyne_rawdata::RawData::pointInRange
bool pointInRange(float range)
Definition: rawdata.h:241
velodyne_rawdata::VLP16_FIRINGS_PER_BLOCK
static const int VLP16_FIRINGS_PER_BLOCK
Definition: rawdata.h:75
velodyne_rawdata::BLOCKS_PER_PACKET
static const int BLOCKS_PER_PACKET
Definition: rawdata.h:108
ros.h
velodyne_rawdata::raw_packet::blocks
raw_block_t blocks[BLOCKS_PER_PACKET]
Definition: rawdata.h:141
velodyne_rawdata::VLS128_TOH_ADJUSTMENT
static const float VLS128_TOH_ADJUSTMENT
Definition: rawdata.h:121
velodyne_rawdata::DataContainerBase
Definition: datacontainerbase.h:47
velodyne_rawdata::two_bytes::bytes
uint8_t bytes[2]
Definition: rawdata.h:104
velodyne_rawdata::RawData::Config::min_range
double min_range
minimum range to publish
Definition: rawdata.h:202
velodyne_rawdata::RawData::RawData
RawData()
Definition: rawdata.cc:49
velodyne_rawdata::VLS128_BANK_1
static const uint16_t VLS128_BANK_1
Definition: rawdata.h:114
velodyne_pointcloud::Calibration
Calibration information for the entire device.
Definition: calibration.h:78
velodyne_rawdata::UPPER_BANK
static const uint16_t UPPER_BANK
Definition: rawdata.h:71
velodyne_rawdata::VLP16_DSR_TOFFSET
static const float VLP16_DSR_TOFFSET
Definition: rawdata.h:78
velodyne_rawdata::RawData::setupSinCosCache
void setupSinCosCache()
Definition: rawdata.cc:294
velodyne_rawdata::RawData::Config::min_angle
int min_angle
minimum angle to publish
Definition: rawdata.h:203
velodyne_rawdata::RawData::buildTimings
bool buildTimings()
setup per-point timing offsets
Definition: rawdata.cc:95
velodyne_rawdata::two_bytes
Definition: rawdata.h:101
velodyne_rawdata::RawData::unpack
void unpack(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data, const ros::Time &scan_start_time)
convert raw packet to point cloud
Definition: rawdata.cc:330
velodyne_rawdata::RawData::sin_rot_table_
float sin_rot_table_[ROTATION_MAX_UNITS]
Definition: rawdata.h:216
velodyne_rawdata::VLS128_BANK_4
static const uint16_t VLS128_BANK_4
Definition: rawdata.h:117
velodyne_rawdata::VLS128_MODEL_ID
static const float VLS128_MODEL_ID
Definition: rawdata.h:123
velodyne_rawdata::raw_block_t
struct velodyne_rawdata::raw_block raw_block_t
Raw Velodyne data block.
velodyne_rawdata::RawData::setup
boost::optional< velodyne_pointcloud::Calibration > setup(ros::NodeHandle private_nh)
Set up for data processing.
Definition: rawdata.cc:220
velodyne_rawdata::RawData::loadCalibration
bool loadCalibration()
Definition: rawdata.cc:284
velodyne_rawdata::VLS128_CHANNEL_TDURATION
static const float VLS128_CHANNEL_TDURATION
Definition: rawdata.h:119
velodyne_rawdata::raw_block::header
uint16_t header
UPPER_BANK or LOWER_BANK.
Definition: rawdata.h:90
velodyne_rawdata::raw_block
Raw Velodyne data block.
Definition: rawdata.h:88
velodyne_rawdata::RawData::setupOffline
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 ...
Definition: rawdata.cc:256
velodyne_rawdata::PACKET_STATUS_SIZE
static const int PACKET_STATUS_SIZE
Definition: rawdata.h:109
velodyne_rawdata::raw_packet_t
struct velodyne_rawdata::raw_packet raw_packet_t
Raw Velodyne packet.
velodyne_rawdata::RawData::calibration_
velodyne_pointcloud::Calibration calibration_
Definition: rawdata.h:215
velodyne_rawdata::two_bytes::uint
uint16_t uint
Definition: rawdata.h:103
velodyne_rawdata::RawData::setupAzimuthCache
void setupAzimuthCache()
Definition: rawdata.cc:311
velodyne_rawdata::RawData::Config::max_angle
int max_angle
maximum angle to publish
Definition: rawdata.h:204
velodyne_rawdata
Definition: datacontainerbase.h:45
velodyne_rawdata::RawData::vls_128_laser_azimuth_cache
float vls_128_laser_azimuth_cache[16]
Definition: rawdata.h:220
velodyne_rawdata::RawData::unpack_vls128
void unpack_vls128(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data, const ros::Time &scan_start_time)
convert raw VLS128 packet to point cloud
Definition: rawdata.cc:509
velodyne_rawdata::raw_packet
Raw Velodyne packet.
Definition: rawdata.h:139
velodyne_rawdata::ROTATION_RESOLUTION
static const float ROTATION_RESOLUTION
Definition: rawdata.h:67
velodyne_rawdata::raw_packet::status
uint8_t status[PACKET_STATUS_SIZE]
Definition: rawdata.h:143
velodyne_rawdata::RawData::cos_rot_table_
float cos_rot_table_[ROTATION_MAX_UNITS]
Definition: rawdata.h:217
velodyne_rawdata::VLS128_DISTANCE_RESOLUTION
static const float VLS128_DISTANCE_RESOLUTION
Definition: rawdata.h:122
velodyne_rawdata::RawData::Config
Definition: rawdata.h:197
velodyne_rawdata::VLP16_FIRING_TOFFSET
static const float VLP16_FIRING_TOFFSET
Definition: rawdata.h:79
velodyne_rawdata::RawData
Velodyne data conversion class.
Definition: rawdata.h:148
velodyne_rawdata::RawData::timing_offsets
std::vector< std::vector< float > > timing_offsets
Definition: rawdata.h:223
ros::Time
velodyne_rawdata::VLS128_BANK_2
static const uint16_t VLS128_BANK_2
Definition: rawdata.h:115
velodyne_rawdata::RawData::setParameters
void setParameters(double min_range, double max_range, double view_direction, double view_width)
Definition: rawdata.cc:52
velodyne_rawdata::raw_block::data
uint8_t data[BLOCK_DATA_SIZE]
Definition: rawdata.h:92
velodyne_rawdata::VLP16_SCANS_PER_FIRING
static const int VLP16_SCANS_PER_FIRING
Definition: rawdata.h:76
velodyne_rawdata::RawData::Config::model
std::string model
Definition: rawdata.h:199
velodyne_rawdata::RawData::unpack_vlp16
void unpack_vlp16(const velodyne_msgs::VelodynePacket &pkt, DataContainerBase &data, const ros::Time &scan_start_time)
convert raw VLP16 packet to point cloud
Definition: rawdata.cc:648
velodyne_rawdata::SCANS_PER_PACKET
static const int SCANS_PER_PACKET
Definition: rawdata.h:110
velodyne_rawdata::RAW_SCAN_SIZE
static const int RAW_SCAN_SIZE
Definition: rawdata.h:63
velodyne_rawdata::SIZE_BLOCK
static const int SIZE_BLOCK
Definition: rawdata.h:62
velodyne_rawdata::VLS128_SEQ_TDURATION
static const float VLS128_SEQ_TDURATION
Definition: rawdata.h:120
velodyne_rawdata::LOWER_BANK
static const uint16_t LOWER_BANK
Definition: rawdata.h:72
velodyne_rawdata::RawData::scansPerPacket
int scansPerPacket() const
Definition: rawdata.cc:80
velodyne_rawdata::RawData::Config::tmp_max_angle
double tmp_max_angle
Definition: rawdata.h:207
calibration.h
velodyne_rawdata::raw_block::rotation
uint16_t rotation
0-35999, divide by 100 to get degrees
Definition: rawdata.h:91
velodyne_rawdata::BLOCK_DATA_SIZE
static const int BLOCK_DATA_SIZE
Definition: rawdata.h:65
velodyne_rawdata::raw_packet::revolution
uint16_t revolution
Definition: rawdata.h:142
velodyne_rawdata::PACKET_SIZE
static const int PACKET_SIZE
Definition: rawdata.h:107
velodyne_rawdata::RawData::Config::calibrationFile
std::string calibrationFile
calibration file name
Definition: rawdata.h:200
velodyne_rawdata::VLS128_BANK_3
static const uint16_t VLS128_BANK_3
Definition: rawdata.h:116
ros::NodeHandle
velodyne_rawdata::RawData::config_
Config config_
Definition: rawdata.h:210
velodyne_rawdata::RawData::Config::max_range
double max_range
maximum range to publish
Definition: rawdata.h:201


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Tue May 2 2023 02:28:04