Velodyne input from PCAP dump file. More...
#include <input.h>

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 | pcap_time_ |
| 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_ |
Velodyne input from PCAP dump file.
Dump files can be grabbed by libpcap, Velodyne's DSR software, ethereal, wireshark, tcpdump, or the Vdump Command.
| 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 |
||
| ) |
|
virtual |
|
virtual |
Get one velodyne packet.
Implements velodyne_driver::Input.
| void velodyne_driver::InputPCAP::setDeviceIP | ( | const std::string & | ip | ) |
|
private |
|
private |