Public Member Functions | Private Attributes
velodyne_driver::InputPCAP Class Reference

Velodyne input from PCAP dump file. More...

#include <input.h>

Inheritance diagram for velodyne_driver::InputPCAP:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual int getPacket (velodyne_msgs::VelodynePacket *pkt)
 Get one velodyne packet.
 InputPCAP (ros::NodeHandle private_nh, double packet_rate, std::string filename="", bool read_once=false, bool read_fast=false, double repeat_delay=0.0)
 constructor
 ~InputPCAP ()

Private Attributes

bool empty_
char errbuf_ [PCAP_ERRBUF_SIZE]
std::string filename_
FILE * fp_
ros::Rate packet_rate_
pcap_t * pcap_
bool read_fast_
bool read_once_
double repeat_delay_

Detailed Description

Velodyne input from PCAP dump file.

Dump files can be grabbed by libpcap, Velodyne's DSR software, ethereal, wireshark, tcpdump, or the Vdump Command.

Definition at line 83 of file input.h.


Constructor & Destructor Documentation

velodyne_driver::InputPCAP::InputPCAP ( ros::NodeHandle  private_nh,
double  packet_rate,
std::string  filename = "",
bool  read_once = false,
bool  read_fast = false,
double  repeat_delay = 0.0 
)

constructor

Parameters:
private_nhprivate node handle for driver
packet_rateexpected device packet frequency (Hz)
filenamePCAP dump file name
read_onceread PCAP in a loop, unless false
read_fastread PCAP at device rate, unless false
repeat_delaytime to wait before repeating PCAP data

Definition at line 185 of file input.cc.

destructor

Definition at line 223 of file input.cc.


Member Function Documentation

int velodyne_driver::InputPCAP::getPacket ( velodyne_msgs::VelodynePacket *  pkt) [virtual]

Get one velodyne packet.

Implements velodyne_driver::Input.

Definition at line 230 of file input.cc.


Member Data Documentation

Definition at line 102 of file input.h.

char velodyne_driver::InputPCAP::errbuf_[PCAP_ERRBUF_SIZE] [private]

Definition at line 101 of file input.h.

Definition at line 98 of file input.h.

Definition at line 99 of file input.h.

Definition at line 106 of file input.h.

Definition at line 100 of file input.h.

Definition at line 104 of file input.h.

Definition at line 103 of file input.h.

Definition at line 105 of file input.h.


The documentation for this class was generated from the following files:


velodyne_driver
Author(s): Jack O'Quin, Patrick Beeson, Michael Quinlan, Yaxin Liu
autogenerated on Thu Aug 27 2015 15:37:02