#include <pf_packet.h>
Public Member Functions | |
int | find_packet_start (uint8_t *buf, size_t buf_len) |
bool | parse_buf (uint8_t *buf, size_t buf_len, size_t &remainder, size_t &p_size) |
virtual void | read_with (PFPacketReader &reader) |
Public Attributes | |
std::vector< uint16_t > | amplitude |
std::vector< uint32_t > | distance |
pf_driver::PFHeader | header |
ros::Time | last_acquired_point_stamp |
Protected Member Functions | |
virtual size_t | get_size ()=0 |
virtual void | get_type (char *p_type)=0 |
virtual void | read_data (uint8_t *buf, size_t num)=0 |
virtual std::tuple< uint16_t, uint32_t, uint16_t > | read_header (ros::serialization::IStream &stream)=0 |
Definition at line 8 of file pf_packet.h.
int PFPacket::find_packet_start | ( | uint8_t * | buf, |
size_t | buf_len | ||
) |
Definition at line 26 of file pf_packet.cpp.
|
protectedpure virtual |
Implemented in PFR2000Packet, and PFR2300Packet.
|
protectedpure virtual |
Implemented in PFR2000Packet_B, PFR2000Packet_A, PFR2000Packet_C, and PFR2300Packet_C1.
bool PFPacket::parse_buf | ( | uint8_t * | buf, |
size_t | buf_len, | ||
size_t & | remainder, | ||
size_t & | p_size | ||
) |
Definition at line 5 of file pf_packet.cpp.
|
protectedpure virtual |
Implemented in PFR2000Packet_B, PFR2000Packet_A, PFR2000Packet_C, and PFR2300Packet_C1.
|
protectedpure virtual |
Implemented in PFR2000Packet, and PFR2300Packet.
|
inlinevirtual |
Reimplemented in PFR2000Packet_B, PFR2000Packet_A, PFR2000Packet_C, and PFR2300Packet_C1.
Definition at line 16 of file pf_packet.h.
std::vector<uint16_t> PFPacket::amplitude |
Definition at line 14 of file pf_packet.h.
std::vector<uint32_t> PFPacket::distance |
Definition at line 13 of file pf_packet.h.
pf_driver::PFHeader PFPacket::header |
Definition at line 12 of file pf_packet.h.
ros::Time PFPacket::last_acquired_point_stamp |
Definition at line 11 of file pf_packet.h.