Public Member Functions | Protected Attributes | List of all members
hfl::HflInterface Class Referenceabstract

Base class for all of the HFL cameras. More...

#include <hfl_interface.h>

Inheritance diagram for hfl::HflInterface:
Inheritance graph
[legend]

Public Member Functions

std::shared_ptr< Frameframe ()
 
virtual double getFrameRate (bool reg_format=false) const =0
 
std::string getModel () const
 
std::string getVersion () const
 
virtual bool parseFrame (int start_byte, const std::vector< uint8_t > &packet)=0
 
virtual bool parseObjects (int start_byte, const std::vector< uint8_t > &packet)=0
 
virtual bool processFrameData (const std::vector< uint8_t > &data)=0
 
virtual bool processObjectData (const std::vector< uint8_t > &data)=0
 
virtual bool processSliceData (const std::vector< uint8_t > &data)=0
 
virtual bool processTelemetryData (const std::vector< uint8_t > &data)=0
 
virtual bool setFrameRate (double rate)=0
 
virtual bool setGlobalRangeOffset (double offset)=0
 

Protected Attributes

std::shared_ptr< hfl::Frameframe_
 Camera's frame configurations. More...
 
uint16_t frame_data_port_
 Camera's UDP frame data port. More...
 
double global_offset_
 global range offset More...
 
std::string ip_address_
 Camera's IP address. More...
 
std::string model_
 Current camera model. More...
 
std::string parent_frame_
 current static tf values More...
 
double pitch_
 
bool publish_tf_
 Current publish tf state. More...
 
double roll_
 
double time_offset_
 time offset More...
 
std::string version_
 Current camera model. More...
 
double x_
 
double y_
 
double yaw_
 
double z_
 

Detailed Description

Base class for all of the HFL cameras.

Definition at line 95 of file hfl_interface.h.

Member Function Documentation

std::shared_ptr< Frame > hfl::HflInterface::frame ( )

Reference to the frame_ member variable

Returns
frame shared_ptr

Definition at line 57 of file hfl_interface.cpp.

virtual double hfl::HflInterface::getFrameRate ( bool  reg_format = false) const
pure virtual

Returns the current frame rate.

Parameters
[in]reg_formatIndicates register format output
Returns
current frame rate

Implemented in hfl::BaseHFL110DCU.

std::string hfl::HflInterface::getModel ( ) const

Gets the Model of the camera.

Returns
string camera model

Definition at line 47 of file hfl_interface.cpp.

std::string hfl::HflInterface::getVersion ( ) const

Gets the camera version.

Returns
string camera model version

Definition at line 52 of file hfl_interface.cpp.

virtual bool hfl::HflInterface::parseFrame ( int  start_byte,
const std::vector< uint8_t > &  packet 
)
pure virtual

Parse packet into depth and intensity image

Parameters
[in]start_bytestarting byte, packet packet data to parse
Returns
bool true if successfully parsed frame data

Implemented in hfl::HFL110DCU.

virtual bool hfl::HflInterface::parseObjects ( int  start_byte,
const std::vector< uint8_t > &  packet 
)
pure virtual

Parse packet into objects

Parameters
[in]start_bytestarting byte, packet packet data to parse
Returns
bool true if successfully parsed object data

Implemented in hfl::HFL110DCU, and hfl::BaseHFL110DCU.

virtual bool hfl::HflInterface::processFrameData ( const std::vector< uint8_t > &  data)
pure virtual

Process the frame data from udp packets

Parameters
[in]dataframe data
Returns
bool

Implemented in hfl::HFL110DCU, and HFL110DCU.

virtual bool hfl::HflInterface::processObjectData ( const std::vector< uint8_t > &  data)
pure virtual

Process the object data from udp packets

Parameters
[in]dataobject data
Returns
bool

Implemented in hfl::HFL110DCU, and hfl::BaseHFL110DCU.

virtual bool hfl::HflInterface::processSliceData ( const std::vector< uint8_t > &  data)
pure virtual

Process the slice data from udp packets

Parameters
[in]dataslice data
Returns
bool

Implemented in hfl::HFL110DCU, and hfl::BaseHFL110DCU.

virtual bool hfl::HflInterface::processTelemetryData ( const std::vector< uint8_t > &  data)
pure virtual

Process the telemetry data from udp packets

Parameters
[in]datatelemetry data
Returns
bool

Implemented in hfl::HFL110DCU, and hfl::BaseHFL110DCU.

virtual bool hfl::HflInterface::setFrameRate ( double  rate)
pure virtual

Set the frame rate.

Parameters
[in]rateCamera frame rate
Returns
bool true if given frame rate set

Implemented in hfl::BaseHFL110DCU.

virtual bool hfl::HflInterface::setGlobalRangeOffset ( double  offset)
pure virtual

Sets global range offset

Parameters
[in]offsetglobal range offset to set
Returns
bool true if given global range offset is set

Implemented in hfl::BaseHFL110DCU.

Member Data Documentation

std::shared_ptr<hfl::Frame> hfl::HflInterface::frame_
protected

Camera's frame configurations.

Definition at line 129 of file hfl_interface.h.

uint16_t hfl::HflInterface::frame_data_port_
protected

Camera's UDP frame data port.

Definition at line 108 of file hfl_interface.h.

double hfl::HflInterface::global_offset_
protected

global range offset

Definition at line 126 of file hfl_interface.h.

std::string hfl::HflInterface::ip_address_
protected

Camera's IP address.

Definition at line 105 of file hfl_interface.h.

std::string hfl::HflInterface::model_
protected

Current camera model.

Definition at line 99 of file hfl_interface.h.

std::string hfl::HflInterface::parent_frame_
protected

current static tf values

Definition at line 114 of file hfl_interface.h.

double hfl::HflInterface::pitch_
protected

Definition at line 119 of file hfl_interface.h.

bool hfl::HflInterface::publish_tf_
protected

Current publish tf state.

Definition at line 111 of file hfl_interface.h.

double hfl::HflInterface::roll_
protected

Definition at line 118 of file hfl_interface.h.

double hfl::HflInterface::time_offset_
protected

time offset

Definition at line 123 of file hfl_interface.h.

std::string hfl::HflInterface::version_
protected

Current camera model.

Definition at line 102 of file hfl_interface.h.

double hfl::HflInterface::x_
protected

Definition at line 115 of file hfl_interface.h.

double hfl::HflInterface::y_
protected

Definition at line 116 of file hfl_interface.h.

double hfl::HflInterface::yaw_
protected

Definition at line 120 of file hfl_interface.h.

double hfl::HflInterface::z_
protected

Definition at line 117 of file hfl_interface.h.


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


hfl_driver
Author(s): Evan Flynn , Maxton Ginier , Gerardo Bravo , Moises Diaz
autogenerated on Sat Mar 20 2021 02:27:31