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;
65 static const int BLOCK_DATA_SIZE = (SCANS_PER_BLOCK * RAW_SCAN_SIZE);
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;
110 static const int SCANS_PER_PACKET = (SCANS_PER_BLOCK * BLOCKS_PER_PACKET);
111 
124 typedef struct raw_packet
125 {
127  uint16_t revolution;
128  uint8_t status[PACKET_STATUS_SIZE];
129 }
131 
133 class RawData
134 {
135 public:
136  RawData();
138  {
139  }
140 
151  boost::optional<velodyne_pointcloud::Calibration> setup(ros::NodeHandle private_nh);
152 
153 
165  int setupOffline(std::string calibration_file, double max_range_, double min_range_);
166 
167  void unpack(const velodyne_msgs::VelodynePacket& pkt, DataContainerBase& data,
168  const ros::Time& scan_start_time);
169 
170  void setParameters(double min_range, double max_range, double view_direction, double view_width);
171 
172  int scansPerPacket() const;
173 
174 private:
176  typedef struct
177  {
178  std::string model;
179  std::string calibrationFile;
180  double max_range;
181  double min_range;
182  int min_angle;
183  int max_angle;
184 
187  }
188  Config;
190 
195  float sin_rot_table_[ROTATION_MAX_UNITS];
196  float cos_rot_table_[ROTATION_MAX_UNITS];
197 
198  // timing offset lookup table
199  std::vector< std::vector<float> > timing_offsets;
200 
207  bool buildTimings();
208 
210  void unpack_vlp16(const velodyne_msgs::VelodynePacket& pkt, DataContainerBase& data,
211  const ros::Time& scan_start_time);
212 };
213 
214 } // namespace velodyne_rawdata
215 
216 #endif // VELODYNE_POINTCLOUD_RAWDATA_H
Raw Velodyne packet.
Definition: rawdata.h:124
static const int PACKET_STATUS_SIZE
Definition: rawdata.h:109
Raw Velodyne data block.
Definition: rawdata.h:88
std::string calibrationFile
calibration file name
Definition: rawdata.h:179
std::vector< std::vector< float > > timing_offsets
Definition: rawdata.h:199
static const int SCANS_PER_BLOCK
Definition: rawdata.h:64
struct velodyne_rawdata::raw_packet raw_packet_t
Raw Velodyne packet.
Calibration information for the entire device.
Definition: calibration.h:78
static const float ROTATION_RESOLUTION
Definition: rawdata.h:67
static const uint16_t UPPER_BANK
Definition: rawdata.h:71
static const int RAW_SCAN_SIZE
Definition: rawdata.h:63
static const float VLP16_FIRING_TOFFSET
Definition: rawdata.h:79
int max_angle
maximum angle to publish
Definition: rawdata.h:183
static const uint16_t ROTATION_MAX_UNITS
Definition: rawdata.h:68
static const int SIZE_BLOCK
Definition: rawdata.h:62
static const int BLOCK_DATA_SIZE
Definition: rawdata.h:65
static const uint16_t LOWER_BANK
Definition: rawdata.h:72
static const float VLP16_DSR_TOFFSET
Definition: rawdata.h:78
uint16_t rotation
0-35999, divide by 100 to get degrees
Definition: rawdata.h:91
static const float VLP16_BLOCK_TDURATION
Definition: rawdata.h:77
int min_angle
minimum angle to publish
Definition: rawdata.h:182
double min_range
minimum range to publish
Definition: rawdata.h:181
double max_range
maximum range to publish
Definition: rawdata.h:180
static const int BLOCKS_PER_PACKET
Definition: rawdata.h:108
static const int VLP16_SCANS_PER_FIRING
Definition: rawdata.h:76
struct velodyne_rawdata::raw_block raw_block_t
Raw Velodyne data block.
uint8_t data[BLOCK_DATA_SIZE]
Definition: rawdata.h:92
Velodyne data conversion class.
Definition: rawdata.h:133
uint16_t header
UPPER_BANK or LOWER_BANK.
Definition: rawdata.h:90
static const int PACKET_SIZE
Definition: rawdata.h:107
static const int VLP16_FIRINGS_PER_BLOCK
Definition: rawdata.h:75
velodyne_pointcloud::Calibration calibration_
Definition: rawdata.h:194
static const int SCANS_PER_PACKET
Definition: rawdata.h:110


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Sun Sep 6 2020 03:25:30