velodyne::InputPCAP Class Reference
Velodyne input from PCAP dump file.
More...
#include <input.h>
List of all members.
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] |
velodyne::InputPCAP::~InputPCAP |
( |
|
) |
[inline] |
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
The documentation for this class was generated from the following files: