#include <errno.h>
#include <stdint.h>
#include <string>
#include <ros/ros.h>
#include <iostream>
#include <cmath>
#include <stdexcept>
#include "duration.h"
#include <sys/time.h>
#include "ros/time.h"
#include <cstdio>
#include <sstream>
#include <log4cxx/logger.h>
#include "ros/console.h"
#include <boost/static_assert.hpp>
#include <cassert>
#include <assert.h>
#include <stddef.h>
#include "ros/assert.h"
#include <vector>
#include <map>
#include <set>
#include <list>
#include <boost/shared_ptr.hpp>
#include <boost/weak_ptr.hpp>
#include <boost/function.hpp>
#include "exceptions.h"
#include <boost/shared_array.hpp>
#include "ros/types.h"
#include "ros/forwards.h"
#include "ros/common.h"
#include "ros/macros.h"
#include <string.h>
#include <boost/array.hpp>
#include "serialized_message.h"
#include "message_forward.h"
#include <boost/utility/enable_if.hpp>
#include <boost/type_traits/remove_const.hpp>
#include <boost/type_traits/remove_reference.hpp>
#include "message_traits.h"
#include "ros/exception.h"
#include <boost/call_traits.hpp>
#include <boost/mpl/and.hpp>
#include <boost/mpl/or.hpp>
#include <boost/mpl/not.hpp>
#include <cstring>
#include <boost/bind.hpp>
#include <typeinfo>
#include <ros/message.h>
#include <boost/type_traits/is_void.hpp>
#include <boost/type_traits/is_base_of.hpp>
#include <boost/type_traits/is_const.hpp>
#include <boost/type_traits/add_const.hpp>
#include <boost/make_shared.hpp>
#include <ros/static_assert.h>
#include "ros/message_traits.h"
#include "ros/builtin_message_traits.h"
#include "ros/serialization.h"
#include "ros/message_event.h"
#include "forwards.h"
#include "timer_options.h"
#include "wall_timer_options.h"
#include "ros/service_traits.h"
#include <boost/lexical_cast.hpp>
#include "subscription_callback_helper.h"
#include "ros/spinner.h"
#include <time.h>
#include "ros/publisher.h"
#include <boost/utility.hpp>
#include "ros/service_server.h"
#include "ros/subscriber.h"
#include "ros/node_handle.h"
#include "ros/init.h"
#include "XmlRpcValue.h"
#include "node_handle.h"
#include "ros/names.h"
#include <ostream>
#include "ros/message_operations.h"
#include <boost/format.hpp>
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... | |
class | velodyne::DataScans |
Convert Velodyne raw input to laserscans format. More... | |
class | velodyne::DataXYZ |
Convert Velodyne raw input to XYZ format. More... | |
struct | velodyne::laserscan |
A single laser scan in Velodyne's frame of reference. More... | |
struct | velodyne::laserscan_xyz |
a single laser scan in XYZ format 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::laserscan | velodyne::laserscan_t |
A single laser scan in Velodyne's frame of reference. | |
typedef struct velodyne::laserscan_xyz | velodyne::laserscan_xyz_t |
a single laser scan in XYZ format | |
typedef struct velodyne::raw_block | velodyne::raw_block_t |
Raw Velodyne data block. | |
typedef void(* | velodyne::raw_callback_t )(const raw_packet_t *raw, size_t npackets) |
type of callback function to receive raw data for one revolution. | |
typedef struct velodyne::raw_packet | velodyne::raw_packet_t |
Raw Velodyne packet. | |
typedef boost::function< void(const std::vector< laserscan_t > &)> | velodyne::scanCallback |
typedef void(* | velodyne::scans_callback_t )(const std::vector< laserscan_t > &scan) |
type of callback function to receive laser scans | |
typedef void(* | velodyne::xyz_callback_t )(const std::vector< laserscan_xyz_t > &scan) |
type of callback function to receive XYZ laser scans | |
typedef boost::function< void(const std::vector< laserscan_xyz_t > &)> | velodyne::xyzCallback |
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 accessors
These classes unpack raw Velodyne LIDAR packets into several useful formats.
velodyne::Data -- virtual base class for unpacking data into various formats
velodyne::DataScans -- derived class, unpacks into vector of individual laser scans
velodyne::DataXYZ -- derived class, unpacks into XYZ format
Definition in file data.h.