alb_reader.h
Go to the documentation of this file.
1 #ifndef _ALB_READER_H
2 #define _ALB_READER_H
3 
4 // Standard headers
5 #include <memory>
6 
7 // Osef headers
8 #include "tcpStream.h"
9 #include "tlvParser.h"
10 
11 // Local headers
12 #include "alb_publisher.h"
13 
15 class AlbReader {
16  public:
17  AlbReader(ros::NodeHandle &nodeHandle);
18 
20  bool init();
21 
26  int parse();
27 
28  private:
33  bool isTlvParsable(const Tlv::tlv_s *frame);
34 
40 
42  void parseInputArguments();
43 
47  int connectToLiveStream();
48 
49  private:
51  std::string ip_v4;
52  int port;
53 
55  std::unique_ptr<uint8_t[]> buffer;
57 };
58 
59 #endif // _ALB_READER_H
AlbReader::parse
int parse()
Parse data from the input stream (ROS callback).
Definition: alb_reader.cpp:48
TcpStreamReader
Definition: tcpStream.h:3
alb_publisher.h
tlvParser.h
AlbReader::AlbReader
AlbReader(ros::NodeHandle &nodeHandle)
Definition: alb_reader.cpp:25
AlbReader::init
bool init()
Initialize the parser.
Definition: alb_reader.cpp:29
tcpStream.h
AlbReader::port
int port
Definition: alb_reader.h:52
AlbReader
Class to read data from the ALB live stream.
Definition: alb_reader.h:15
AlbReader::isTlvParsable
bool isTlvParsable(const Tlv::tlv_s *frame)
Check if the TLV is parsable.
Definition: alb_reader.cpp:68
AlbReader::buffer
std::unique_ptr< uint8_t[]> buffer
Definition: alb_reader.h:55
AlbPublisher
Class to publish ROS messages from the ALB.
Definition: alb_publisher.h:19
AlbReader::alb_initialized
bool alb_initialized
Definition: alb_reader.h:56
AlbReader::tcp_reader
TcpStreamReader tcp_reader
Definition: alb_reader.h:50
AlbReader::parseInputArguments
void parseInputArguments()
Parse the ROS input arguments.
Definition: alb_reader.cpp:97
AlbReader::ip_v4
std::string ip_v4
Definition: alb_reader.h:51
ros::NodeHandle
AlbReader::areInputArgumentsValid
bool areInputArgumentsValid()
Check if input arguments are valid.
Definition: alb_reader.cpp:85
AlbReader::alb_publisher
AlbPublisher alb_publisher
Definition: alb_reader.h:54
AlbReader::connectToLiveStream
int connectToLiveStream()
Connect the parser to a live stream.
Definition: alb_reader.cpp:104


outsight_alb_driver
Author(s): Outsight
autogenerated on Thu Oct 13 2022 02:21:45