Public Member Functions | Private Attributes | List of all members
velodyne_driver::InputPCAP Class Reference

Velodyne input from PCAP dump file. More...

#include <input.h>

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

Public Member Functions

virtual int getPacket (velodyne_msgs::VelodynePacket *pkt, const double time_offset)
 Get one velodyne packet. More...
 
 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 More...
 
void setDeviceIP (const std::string &ip)
 
virtual ~InputPCAP ()
 
- Public Member Functions inherited from velodyne_driver::Input
 Input (ros::NodeHandle private_nh, uint16_t port)
 constructor More...
 
virtual ~Input ()
 

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_
 

Additional Inherited Members

- Protected Attributes inherited from velodyne_driver::Input
std::string devip_str_
 
bool gps_time_
 
uint16_t port_
 
ros::NodeHandle private_nh_
 

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.

velodyne_driver::InputPCAP::~InputPCAP ( void  )
virtual

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

bool velodyne_driver::InputPCAP::empty_
private

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.

std::string velodyne_driver::InputPCAP::filename_
private

Definition at line 137 of file input.h.

ros::Rate velodyne_driver::InputPCAP::packet_rate_
private

Definition at line 136 of file input.h.

pcap_t* velodyne_driver::InputPCAP::pcap_
private

Definition at line 138 of file input.h.

bpf_program velodyne_driver::InputPCAP::pcap_packet_filter_
private

Definition at line 139 of file input.h.

bool velodyne_driver::InputPCAP::read_fast_
private

Definition at line 143 of file input.h.

bool velodyne_driver::InputPCAP::read_once_
private

Definition at line 142 of file input.h.

double velodyne_driver::InputPCAP::repeat_delay_
private

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 Sun Sep 6 2020 03:25:28