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. | |
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_ |
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 |
||
) |
velodyne_driver::InputPCAP::~InputPCAP | ( | void | ) | [virtual] |
int velodyne_driver::InputPCAP::getPacket | ( | velodyne_msgs::VelodynePacket * | pkt, |
const double | time_offset | ||
) | [virtual] |
Get one velodyne packet.
Implements velodyne_driver::Input.
void velodyne_driver::InputPCAP::setDeviceIP | ( | const std::string & | ip | ) |
bool velodyne_driver::InputPCAP::empty_ [private] |
char velodyne_driver::InputPCAP::errbuf_[PCAP_ERRBUF_SIZE] [private] |
std::string velodyne_driver::InputPCAP::filename_ [private] |
pcap_t* velodyne_driver::InputPCAP::pcap_ [private] |
bpf_program velodyne_driver::InputPCAP::pcap_packet_filter_ [private] |
bool velodyne_driver::InputPCAP::read_fast_ [private] |
bool velodyne_driver::InputPCAP::read_once_ [private] |
double velodyne_driver::InputPCAP::repeat_delay_ [private] |