Public Member Functions | Private Member Functions | Private Attributes | List of all members
AlbReader Class Reference

Class to read data from the ALB live stream. More...

#include <alb_reader.h>

Public Member Functions

 AlbReader (ros::NodeHandle &nodeHandle)
 
bool init ()
 Initialize the parser. More...
 
int parse ()
 Parse data from the input stream (ROS callback). More...
 

Private Member Functions

bool areInputArgumentsValid ()
 Check if input arguments are valid. More...
 
int connectToLiveStream ()
 Connect the parser to a live stream. More...
 
bool isTlvParsable (const Tlv::tlv_s *frame)
 Check if the TLV is parsable. More...
 
void parseInputArguments ()
 Parse the ROS input arguments. More...
 

Private Attributes

bool alb_initialized
 
AlbPublisher alb_publisher
 
std::unique_ptr< uint8_t[]> buffer
 
std::string ip_v4
 
int port
 
TcpStreamReader tcp_reader
 

Detailed Description

Class to read data from the ALB live stream.

Definition at line 15 of file alb_reader.h.

Constructor & Destructor Documentation

◆ AlbReader()

AlbReader::AlbReader ( ros::NodeHandle nodeHandle)

Definition at line 25 of file alb_reader.cpp.

Member Function Documentation

◆ areInputArgumentsValid()

bool AlbReader::areInputArgumentsValid ( )
private

Check if input arguments are valid.

Returns
  • True if arguments are valid.
  • False in case of error.

Definition at line 85 of file alb_reader.cpp.

◆ connectToLiveStream()

int AlbReader::connectToLiveStream ( )
private

Connect the parser to a live stream.

Returns
  • Error code.

Definition at line 104 of file alb_reader.cpp.

◆ init()

bool AlbReader::init ( )

Initialize the parser.

Definition at line 29 of file alb_reader.cpp.

◆ isTlvParsable()

bool AlbReader::isTlvParsable ( const Tlv::tlv_s *  frame)
private

Check if the TLV is parsable.

Returns
  • True if parsing is possible.
  • False if not.

Definition at line 68 of file alb_reader.cpp.

◆ parse()

int AlbReader::parse ( )

Parse data from the input stream (ROS callback).

Returns
  • 0 on success.
  • -1 on error.

Definition at line 48 of file alb_reader.cpp.

◆ parseInputArguments()

void AlbReader::parseInputArguments ( )
private

Parse the ROS input arguments.

Definition at line 97 of file alb_reader.cpp.

Member Data Documentation

◆ alb_initialized

bool AlbReader::alb_initialized
private

Definition at line 56 of file alb_reader.h.

◆ alb_publisher

AlbPublisher AlbReader::alb_publisher
private

Definition at line 54 of file alb_reader.h.

◆ buffer

std::unique_ptr<uint8_t[]> AlbReader::buffer
private

Definition at line 55 of file alb_reader.h.

◆ ip_v4

std::string AlbReader::ip_v4
private

Definition at line 51 of file alb_reader.h.

◆ port

int AlbReader::port
private

Definition at line 52 of file alb_reader.h.

◆ tcp_reader

TcpStreamReader AlbReader::tcp_reader
private

Definition at line 50 of file alb_reader.h.


The documentation for this class was generated from the following files:


outsight_alb_driver
Author(s): Outsight
autogenerated on Fri Oct 14 2022 02:29:51