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 
51 #include <ros/ros.h>
52 #include <velodyne_msgs/VelodyneScan.h>
55 
56 namespace velodyne_rawdata
57 {
61 static const int SIZE_BLOCK = 100;
62 static const int RAW_SCAN_SIZE = 3;
63 static const int SCANS_PER_BLOCK = 32;
64 static const int BLOCK_DATA_SIZE = (SCANS_PER_BLOCK * RAW_SCAN_SIZE);
65 
66 static const float ROTATION_RESOLUTION = 0.01f; // [deg]
67 static const uint16_t ROTATION_MAX_UNITS = 36000u; // [deg/100]
68 
70 static const uint16_t UPPER_BANK = 0xeeff;
71 static const uint16_t LOWER_BANK = 0xddff;
72 
74 static const int VLP16_FIRINGS_PER_BLOCK = 2;
75 static const int VLP16_SCANS_PER_FIRING = 16;
76 static const float VLP16_BLOCK_TDURATION = 110.592f; // [µs]
77 static const float VLP16_DSR_TOFFSET = 2.304f; // [µs]
78 static const float VLP16_FIRING_TOFFSET = 55.296f; // [µs]
79 
87 typedef struct raw_block
88 {
89  uint16_t header;
90  uint16_t rotation;
92 }
94 
101 {
102  uint16_t uint;
103  uint8_t bytes[2];
104 };
105 
106 static const int PACKET_SIZE = 1206;
107 static const int BLOCKS_PER_PACKET = 12;
108 static const int PACKET_STATUS_SIZE = 4;
109 static const int SCANS_PER_PACKET = (SCANS_PER_BLOCK * BLOCKS_PER_PACKET);
110 
123 typedef struct raw_packet
124 {
126  uint16_t revolution;
127  uint8_t status[PACKET_STATUS_SIZE];
128 }
130 
132 class RawData
133 {
134 public:
135  RawData();
137  {
138  }
139 
150  boost::optional<velodyne_pointcloud::Calibration> setup(ros::NodeHandle private_nh);
151 
163  int setupOffline(std::string calibration_file, double max_range_, double min_range_);
164 
165  void unpack(const velodyne_msgs::VelodynePacket& pkt, DataContainerBase& data);
166 
167  void setParameters(double min_range, double max_range, double view_direction, double view_width);
168 
169  int scansPerPacket() const;
170 
171 private:
173  typedef struct
174  {
175  std::string calibrationFile;
176  double max_range;
177  double min_range;
178  int min_angle;
179  int max_angle;
180 
183  }
184  Config;
186 
191  float sin_rot_table_[ROTATION_MAX_UNITS];
192  float cos_rot_table_[ROTATION_MAX_UNITS];
193 
195  void unpack_vlp16(const velodyne_msgs::VelodynePacket& pkt, DataContainerBase& data);
196 };
197 
198 } // namespace velodyne_rawdata
199 
200 #endif // VELODYNE_POINTCLOUD_RAWDATA_H
Raw Velodyne packet.
Definition: rawdata.h:123
static const int PACKET_STATUS_SIZE
Definition: rawdata.h:108
Raw Velodyne data block.
Definition: rawdata.h:87
std::string calibrationFile
calibration file name
Definition: rawdata.h:175
static const int SCANS_PER_BLOCK
Definition: rawdata.h:63
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:66
static const uint16_t UPPER_BANK
Definition: rawdata.h:70
static const int RAW_SCAN_SIZE
Definition: rawdata.h:62
static const float VLP16_FIRING_TOFFSET
Definition: rawdata.h:78
int max_angle
maximum angle to publish
Definition: rawdata.h:179
static const uint16_t ROTATION_MAX_UNITS
Definition: rawdata.h:67
static const int SIZE_BLOCK
Definition: rawdata.h:61
static const int BLOCK_DATA_SIZE
Definition: rawdata.h:64
static const uint16_t LOWER_BANK
Definition: rawdata.h:71
static const float VLP16_DSR_TOFFSET
Definition: rawdata.h:77
uint16_t rotation
0-35999, divide by 100 to get degrees
Definition: rawdata.h:90
static const float VLP16_BLOCK_TDURATION
Definition: rawdata.h:76
int min_angle
minimum angle to publish
Definition: rawdata.h:178
double min_range
minimum range to publish
Definition: rawdata.h:177
double max_range
maximum range to publish
Definition: rawdata.h:176
static const int BLOCKS_PER_PACKET
Definition: rawdata.h:107
static const int VLP16_SCANS_PER_FIRING
Definition: rawdata.h:75
struct velodyne_rawdata::raw_block raw_block_t
Raw Velodyne data block.
uint8_t data[BLOCK_DATA_SIZE]
Definition: rawdata.h:91
Velodyne data conversion class.
Definition: rawdata.h:132
uint16_t header
UPPER_BANK or LOWER_BANK.
Definition: rawdata.h:89
static const int PACKET_SIZE
Definition: rawdata.h:106
static const int VLP16_FIRINGS_PER_BLOCK
Definition: rawdata.h:74
velodyne_pointcloud::Calibration calibration_
Definition: rawdata.h:190
static const int SCANS_PER_PACKET
Definition: rawdata.h:109


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Thu Jul 4 2019 19:09:30