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, const double time_offset)
 Get one velodyne packet.
 InputPCAP (ros::NodeHandle private_nh, uint16_t port=DATA_PORT_NUMBER, double packet_rate=0.0, std::string filename="", bool read_once=false, bool read_fast=false, double repeat_delay=0.0)
 constructor
void setDeviceIP (const std::string &ip)
virtual ~InputPCAP ()

Private Attributes

bool empty_
char errbuf_ [PCAP_ERRBUF_SIZE]
std::string filename_
ros::Rate packet_rate_
pcap_t * pcap_
bpf_program pcap_packet_filter_
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 119 of file input.h.


Constructor & Destructor Documentation

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

constructor

Parameters:
private_nhROS private handle for calling node.
portUDP port number
packet_rateexpected device packet frequency (Hz)
filenamePCAP dump file name

Definition at line 251 of file input.cc.

destructor

Definition at line 293 of file input.cc.


Member Function Documentation

int velodyne_driver::InputPCAP::getPacket ( velodyne_msgs::VelodynePacket *  pkt,
const double  time_offset 
) [virtual]

Get one velodyne packet.

Implements velodyne_driver::Input.

Definition at line 299 of file input.cc.

void velodyne_driver::InputPCAP::setDeviceIP ( const std::string &  ip)

Member Data Documentation

Definition at line 141 of file input.h.

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

Definition at line 140 of file input.h.

Definition at line 137 of file input.h.

Definition at line 136 of file input.h.

Definition at line 138 of file input.h.

Definition at line 139 of file input.h.

Definition at line 143 of file input.h.

Definition at line 142 of file input.h.

Definition at line 144 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 Wed Jul 3 2019 19:32:21