rawdata.h
Go to the documentation of this file.
00001 // Copyright (C) 2007, 2009, 2010, 2012, 2019 Yaxin Liu, Patrick Beeson, Jack O'Quin, Joshua Whitley
00002 // All rights reserved.
00003 //
00004 // Software License Agreement (BSD License 2.0)
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions
00008 // are met:
00009 //
00010 //  * Redistributions of source code must retain the above copyright
00011 //    notice, this list of conditions and the following disclaimer.
00012 //  * Redistributions in binary form must reproduce the above
00013 //    copyright notice, this list of conditions and the following
00014 //    disclaimer in the documentation and/or other materials provided
00015 //    with the distribution.
00016 //  * Neither the name of {copyright_holder} nor the names of its
00017 //    contributors may be used to endorse or promote products derived
00018 //    from this software without specific prior written permission.
00019 //
00020 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00021 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00022 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00023 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00024 // COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00025 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00026 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00027 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00028 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00029 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00030 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00031 // POSSIBILITY OF SUCH DAMAGE.
00032 
00042 #ifndef VELODYNE_POINTCLOUD_RAWDATA_H
00043 #define VELODYNE_POINTCLOUD_RAWDATA_H
00044 
00045 #include <errno.h>
00046 #include <stdint.h>
00047 #include <string>
00048 #include <boost/format.hpp>
00049 #include <math.h>
00050 
00051 #include <ros/ros.h>
00052 #include <velodyne_msgs/VelodyneScan.h>
00053 #include <velodyne_pointcloud/calibration.h>
00054 #include <velodyne_pointcloud/datacontainerbase.h>
00055 
00056 namespace velodyne_rawdata
00057 {
00061 static const int SIZE_BLOCK = 100;
00062 static const int RAW_SCAN_SIZE = 3;
00063 static const int SCANS_PER_BLOCK = 32;
00064 static const int BLOCK_DATA_SIZE = (SCANS_PER_BLOCK * RAW_SCAN_SIZE);
00065 
00066 static const float ROTATION_RESOLUTION = 0.01f;     // [deg]
00067 static const uint16_t ROTATION_MAX_UNITS = 36000u;  // [deg/100]
00068 
00070 static const uint16_t UPPER_BANK = 0xeeff;
00071 static const uint16_t LOWER_BANK = 0xddff;
00072 
00074 static const int VLP16_FIRINGS_PER_BLOCK = 2;
00075 static const int VLP16_SCANS_PER_FIRING = 16;
00076 static const float VLP16_BLOCK_TDURATION = 110.592f;  // [µs]
00077 static const float VLP16_DSR_TOFFSET = 2.304f;        // [µs]
00078 static const float VLP16_FIRING_TOFFSET = 55.296f;    // [µs]
00079 
00087 typedef struct raw_block
00088 {
00089   uint16_t header;    
00090   uint16_t rotation;  
00091   uint8_t data[BLOCK_DATA_SIZE];
00092 }
00093 raw_block_t;
00094 
00100 union two_bytes
00101 {
00102   uint16_t uint;
00103   uint8_t bytes[2];
00104 };
00105 
00106 static const int PACKET_SIZE = 1206;
00107 static const int BLOCKS_PER_PACKET = 12;
00108 static const int PACKET_STATUS_SIZE = 4;
00109 static const int SCANS_PER_PACKET = (SCANS_PER_BLOCK * BLOCKS_PER_PACKET);
00110 
00123 typedef struct raw_packet
00124 {
00125   raw_block_t blocks[BLOCKS_PER_PACKET];
00126   uint16_t revolution;
00127   uint8_t status[PACKET_STATUS_SIZE];
00128 }
00129 raw_packet_t;
00130 
00132 class RawData
00133 {
00134 public:
00135   RawData();
00136   ~RawData()
00137   {
00138   }
00139 
00150   boost::optional<velodyne_pointcloud::Calibration> setup(ros::NodeHandle private_nh);
00151 
00163   int setupOffline(std::string calibration_file, double max_range_, double min_range_);
00164 
00165   void unpack(const velodyne_msgs::VelodynePacket& pkt, DataContainerBase& data);
00166 
00167   void setParameters(double min_range, double max_range, double view_direction, double view_width);
00168 
00169   int scansPerPacket() const;
00170 
00171 private:
00173   typedef struct
00174   {
00175     std::string calibrationFile;  
00176     double max_range;             
00177     double min_range;             
00178     int min_angle;                
00179     int max_angle;                
00180 
00181     double tmp_min_angle;
00182     double tmp_max_angle;
00183   }
00184   Config;
00185   Config config_;
00186 
00190   velodyne_pointcloud::Calibration calibration_;
00191   float sin_rot_table_[ROTATION_MAX_UNITS];
00192   float cos_rot_table_[ROTATION_MAX_UNITS];
00193 
00195   void unpack_vlp16(const velodyne_msgs::VelodynePacket& pkt, DataContainerBase& data);
00196 };
00197 
00198 }  // namespace velodyne_rawdata
00199 
00200 #endif  // VELODYNE_POINTCLOUD_RAWDATA_H


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Wed Jul 3 2019 19:32:23