pf_packet.h
Go to the documentation of this file.
1 #pragma once
2 
3 #include <ros/serialization.h>
4 #include "pf_driver/PFHeader.h"
5 
6 class PFPacketReader;
7 
8 class PFPacket
9 {
10 public:
12  pf_driver::PFHeader header;
13  std::vector<uint32_t> distance;
14  std::vector<uint16_t> amplitude;
15 
16  virtual void read_with(PFPacketReader& reader)
17  {
18  }
19 
20  int find_packet_start(uint8_t* buf, size_t buf_len);
21  bool parse_buf(uint8_t* buf, size_t buf_len, size_t& remainder, size_t& p_size);
22 
23 protected:
24  virtual size_t get_size() = 0;
25  virtual void get_type(char* p_type) = 0;
26  virtual std::tuple<uint16_t, uint32_t, uint16_t> read_header(ros::serialization::IStream& stream) = 0;
27  virtual void read_data(uint8_t* buf, size_t num) = 0;
28 };
virtual std::tuple< uint16_t, uint32_t, uint16_t > read_header(ros::serialization::IStream &stream)=0
ros::Time last_acquired_point_stamp
Definition: pf_packet.h:11
bool parse_buf(uint8_t *buf, size_t buf_len, size_t &remainder, size_t &p_size)
Definition: pf_packet.cpp:5
virtual void read_with(PFPacketReader &reader)
Definition: pf_packet.h:16
virtual size_t get_size()=0
virtual void read_data(uint8_t *buf, size_t num)=0
int find_packet_start(uint8_t *buf, size_t buf_len)
Definition: pf_packet.cpp:26
std::vector< uint16_t > amplitude
Definition: pf_packet.h:14
std::vector< uint32_t > distance
Definition: pf_packet.h:13
virtual void get_type(char *p_type)=0
pf_driver::PFHeader header
Definition: pf_packet.h:12


pf_driver
Author(s): Harsh Deshpande
autogenerated on Fri Feb 24 2023 03:59:35