#include <errno.h>
#include <stdint.h>
#include <string>
#include <boost/format.hpp>
#include <ros/ros.h>
#include <velodyne_common/RawScan.h>
#include <velodyne_msgs/VelodyneScan.h>
#include <vector>
#include <ostream>
#include "ros/serialization.h"
#include "ros/builtin_message_traits.h"
#include "ros/message_operations.h"
#include "ros/message.h"
#include "ros/time.h"
#include "std_msgs/Header.h"
Go to the source code of this file.
Classes | |
struct | Velodyne::correction_angles |
Correction angles for a specific HDL-64E device. More... | |
class | Velodyne::Data |
Base Velodyne data class -- not used directly. More... | |
struct | Velodyne::raw_block |
Raw Velodyne data block. More... | |
struct | Velodyne::raw_packet |
Raw Velodyne packet. More... | |
union | Velodyne::two_bytes |
Namespaces | |
namespace | Velodyne |
Typedefs | |
typedef struct Velodyne::raw_block | Velodyne::raw_block_t |
Raw Velodyne data block. | |
typedef struct Velodyne::raw_packet | Velodyne::raw_packet_t |
Raw Velodyne packet. | |
Variables | |
static const int | Velodyne::BLOCK_DATA_SIZE = (SCANS_PER_BLOCK * RAW_SCAN_SIZE) |
static const int | Velodyne::BLOCKS_PER_PACKET = 12 |
static const float | Velodyne::DISTANCE_MAX = 130.0f |
static const float | Velodyne::DISTANCE_MAX_UNITS |
static const float | Velodyne::DISTANCE_RESOLUTION = 0.002f |
static const uint16_t | Velodyne::LOWER_BANK = 0xddff |
static const int | Velodyne::PACKET_SIZE = 1206 |
static const int | Velodyne::PACKET_STATUS_SIZE = 4 |
static const int | Velodyne::PACKETS_PER_REV = 260 |
static const int | Velodyne::RAW_SCAN_SIZE = 3 |
static const float | Velodyne::ROTATION_MAX_UNITS = 36000 |
static const float | Velodyne::ROTATION_RESOLUTION = 0.01f |
static const int | Velodyne::SCANS_PER_BLOCK = 32 |
static const int | Velodyne::SCANS_PER_PACKET = (SCANS_PER_BLOCK * BLOCKS_PER_PACKET) |
static const int | Velodyne::SCANS_PER_REV = (SCANS_PER_PACKET * PACKETS_PER_REV) |
static const int | Velodyne::SIZE_BLOCK = 100 |
static const uint16_t | Velodyne::UPPER_BANK = 0xeeff |
Velodyne HDL-64E 3D LIDAR data accessor base class.
Base class for unpacking raw Velodyne LIDAR packets into various useful formats.
Definition in file data_base.h.