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

Public Member Functions | |
| virtual int | getPacket (pcl::PointCloud< pcl::PointXYZI > &pc) |
| Get one o3m151 packet. More... | |
| InputPCAP (ros::NodeHandle private_nh, double packet_rate, std::string filename="", bool read_once=false, bool read_fast=false, double repeat_delay=0.0) | |
| constructor More... | |
| ~InputPCAP () | |
Public Member Functions inherited from o3m151_driver::Input | |
| Input () | |
Private Attributes | |
| bool | empty_ |
| char | errbuf_ [PCAP_ERRBUF_SIZE] |
| std::string | filename_ |
| FILE * | fp_ |
| ros::Rate | packet_rate_ |
| pcap_t * | pcap_ |
| bool | read_fast_ |
| bool | read_once_ |
| double | repeat_delay_ |
Additional Inherited Members | |
Protected Member Functions inherited from o3m151_driver::Input | |
| int | process (int8_t *udpPacketBuf, const ssize_t rc, pcl::PointCloud< pcl::PointXYZI > &pc) |
| void | processChannel8 (int8_t *buf, uint32_t size, pcl::PointCloud< pcl::PointXYZI > &pc) |
| int | processPacket (int8_t *currentPacketData, uint32_t currentPacketSize, int8_t *channelBuffer, uint32_t channelBufferSize, uint32_t *pos) |
| double | slope (const std::vector< double > &x, const std::vector< double > &y) |
Protected Attributes inherited from o3m151_driver::Input | |
| uint32_t | channel_buf_size_ |
| int8_t * | channelBuf |
| uint32_t | pos_in_channel_ |
| uint32_t | previous_packet_counter_ |
| bool | previous_packet_counter_valid_ |
| bool | startOfChannelFound_ |
O3M151 input from PCAP dump file.
Dump files can be grabbed by libpcap, ethereal, wireshark, tcpdump, or the Vdump Command.
| o3m151_driver::InputPCAP::InputPCAP | ( | ros::NodeHandle | private_nh, |
| double | packet_rate, | ||
| std::string | filename = "", |
||
| bool | read_once = false, |
||
| bool | read_fast = false, |
||
| double | repeat_delay = 0.0 |
||
| ) |
constructor
| private_nh | private node handle for driver |
| packet_rate | expected device packet frequency (Hz) |
| filename | PCAP dump file name |
| read_once | read PCAP in a loop, unless false |
| read_fast | read PCAP at device rate, unless false |
| repeat_delay | time to wait before repeating PCAP data |
|
virtual |
|
private |