00001 /* -*- mode: C++ -*- 00002 * 00003 * Copyright (C) 2007 Austin Robot Technology, Yaxin Liu, Patrick Beeson 00004 * Copyright (C) 2009, 2010 Austin Robot Technology, Jack O'Quin 00005 * 00006 * License: Modified BSD Software License Agreement 00007 * 00008 * $Id: data_base.h 818 2010-11-20 01:43:43Z jack.oquin $ 00009 */ 00010 00023 #ifndef __VELODYNE_DATA_BASE_H 00024 #define __VELODYNE_DATA_BASE_H 00025 00026 #include <errno.h> 00027 #include <stdint.h> 00028 #include <string> 00029 #include <boost/format.hpp> 00030 00031 #include <ros/ros.h> 00032 #include <velodyne_common/RawScan.h> 00033 #include <velodyne_msgs/VelodyneScan.h> 00034 00035 namespace Velodyne 00036 { 00037 00041 static const int SIZE_BLOCK = 100; 00042 static const int RAW_SCAN_SIZE = 3; 00043 static const int SCANS_PER_BLOCK = 32; 00044 static const int BLOCK_DATA_SIZE = (SCANS_PER_BLOCK * RAW_SCAN_SIZE); 00045 00046 static const float ROTATION_RESOLUTION = 0.01f; 00047 static const float ROTATION_MAX_UNITS = 36000; 00051 static const float DISTANCE_MAX = 130.0f; 00052 static const float DISTANCE_RESOLUTION = 0.002f; 00053 static const float DISTANCE_MAX_UNITS = (DISTANCE_MAX 00054 / DISTANCE_RESOLUTION + 1.0); 00055 static const uint16_t UPPER_BANK = 0xeeff; 00056 static const uint16_t LOWER_BANK = 0xddff; 00057 00065 typedef struct raw_block 00066 { 00067 uint16_t header; 00068 uint16_t rotation; 00069 uint8_t data[BLOCK_DATA_SIZE]; 00070 } raw_block_t; 00071 00077 union two_bytes 00078 { 00079 uint16_t uint; 00080 uint8_t bytes[2]; 00081 }; 00082 00083 static const int PACKET_SIZE = 1206; 00084 static const int BLOCKS_PER_PACKET = 12; 00085 static const int PACKET_STATUS_SIZE = 4; 00086 static const int SCANS_PER_PACKET = (SCANS_PER_BLOCK * BLOCKS_PER_PACKET); 00087 static const int PACKETS_PER_REV = 260; 00088 static const int SCANS_PER_REV = (SCANS_PER_PACKET * PACKETS_PER_REV); 00089 00102 typedef struct raw_packet 00103 { 00104 raw_block_t blocks[BLOCKS_PER_PACKET]; 00105 uint16_t revolution; 00106 uint8_t status[PACKET_STATUS_SIZE]; 00107 } raw_packet_t; 00108 00110 struct correction_angles 00111 { 00112 float rotational; 00113 float vertical; 00114 float offset1, offset2, offset3; 00115 int enabled; 00116 }; 00117 00119 class Data 00120 { 00121 public: 00122 Data(std::string ofile="", std::string anglesFile=""); 00123 00124 virtual ~Data() {} 00125 00133 virtual int getParams(void); 00134 00140 virtual int print(void) = 0; 00141 00153 void processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg); 00154 00159 virtual void processPacket(const velodyne_msgs::VelodynePacket *pkt, 00160 const std::string &frame_id) = 0; 00161 00173 virtual int setup(void); 00174 00176 virtual void shutdown(void) 00177 { 00178 ros::shutdown(); // break out of main ros::spin() 00179 uninitialized_ = true; 00180 } 00181 00182 protected: 00183 00185 std::string ofile_; 00186 std::string anglesFile_; 00187 00189 FILE *ofp_; 00190 bool uninitialized_; 00191 00193 velodyne_msgs::VelodyneScan::ConstPtr rawScan_; 00194 00199 correction_angles lower_[SCANS_PER_BLOCK]; 00200 correction_angles upper_[SCANS_PER_BLOCK]; 00201 }; 00202 00203 } // velodyne namespace 00204 00205 #endif // __VELODYNE_DATA_BASE_H