velodyne::InputPCAP Class Reference

Velodyne input from PCAP dump file. More...

#include <input.h>

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

List of all members.

Public Member Functions

virtual int getPackets (uint8_t *buffer, int npacks, double *data_time)
 Read velodyne packets.
 InputPCAP (std::string filename="", bool read_once=false, bool read_fast=false, double repeat_delay=0.0)
virtual int vclose (void)
 Close the data socket or file.
virtual int vopen (void)
 Open the data socket or file.
 ~InputPCAP ()

Private Attributes

ros::Rate delay_
bool empty_
char errbuf_ [PCAP_ERRBUF_SIZE]
std::string filename_
FILE * fp_
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 121 of file input.h.


Constructor & Destructor Documentation

velodyne::InputPCAP::InputPCAP ( std::string  filename = "",
bool  read_once = false,
bool  read_fast = false,
double  repeat_delay = 0.0 
) [inline]

Definition at line 124 of file input.h.

velodyne::InputPCAP::~InputPCAP (  )  [inline]

Definition at line 149 of file input.h.


Member Function Documentation

int velodyne::InputPCAP::getPackets ( uint8_t *  buffer,
int  npacks,
double *  data_time 
) [virtual]

Read velodyne packets.

Parameters:
buffer array to receive raw data packets
npacks number of packets to read
data_time[out] average time when data received
Returns:
number of packets not read, if any 0 if successful, -1 if end of file
Deprecated:
Use getPacket() instead

Implements velodyne::Input.

Definition at line 198 of file input.cc.

int velodyne::InputPCAP::vclose ( void   )  [virtual]

Close the data socket or file.

Returns:
0, if successful errno value, for failure

Implements velodyne::Input.

Definition at line 262 of file input.cc.

int velodyne::InputPCAP::vopen ( void   )  [virtual]

Open the data socket or file.

Returns:
: 0, if successful; -1 for failure
Todo:
return errno value for failure

Todo:
print error message, if pcap open fails

Implements velodyne::Input.

Definition at line 173 of file input.cc.


Member Data Documentation

ros::Rate velodyne::InputPCAP::delay_ [private]

Definition at line 164 of file input.h.

Definition at line 160 of file input.h.

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

Definition at line 159 of file input.h.

std::string velodyne::InputPCAP::filename_ [private]

Definition at line 156 of file input.h.

FILE* velodyne::InputPCAP::fp_ [private]

Definition at line 157 of file input.h.

pcap_t* velodyne::InputPCAP::pcap_ [private]

Definition at line 158 of file input.h.

Definition at line 162 of file input.h.

Definition at line 161 of file input.h.

Definition at line 163 of file input.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerator Defines


velodyne_common
Author(s): Jack O'Quin, Patrick Beeson, Michael Quinlan, Yaxin Liu
autogenerated on Fri Jan 11 10:05:58 2013