Public Member Functions | Protected Attributes | List of all members
IInputSensor Class Referenceabstract

This is input base class. More...

#include <input_sensor.h>

Inheritance diagram for IInputSensor:
Inheritance graph
[legend]

Public Member Functions

virtual void closeSensor ()=0
 
virtual void configureSensor (int camera_mode)=0
 
virtual void getExtrinsics (CameraExtrinsics *camera_extrinsics)=0
 
int getFrameCounter ()
 Get the current Frame count value. More...
 
int getFrameHeight ()
 Get the Frame Height object Only integer scaling is supported. More...
 
virtual bool getFrameTimestamp (ros::Time *timestamp)=0
 
int getFrameWidth ()
 Get the Frame Width object Only integer scaling is supported. More...
 
virtual void getIntrinsics (CameraIntrinsics *camera_intrinsics)=0
 
bool isOpened ()
 function to check whether input is opened More...
 
virtual void openSensor (std::string sensor_name, int input_image_width, int input_image_height, std::string config_file_name, std::string input_sensor_ip)=0
 
virtual bool readNextFrame (unsigned short *depth_frame, unsigned short *ab_frame, unsigned short *conf_frame, short *xyz_frame)=0
 
virtual void setABinvalidationThreshold (int threshold)=0
 
virtual void setConfidenceThreshold (int threshold)=0
 
void setFrameHeight (int frm_height)
 Sett the Frame Height object Only integer scaling is supported. More...
 
void setFrameWidth (int frm_width)
 Set the Frame Width object Only integer scaling is supported. More...
 
virtual void setJBLFFilterSize (int jblf_filter_size)=0
 
virtual void setJBLFFilterState (bool jblf_filter_state)=0
 
void setProcessingScale (int scale_factor)
 Set the Processing Scale object. More...
 
virtual void setRadialFilterMaxThreshold (int radial_max_threshold)=0
 
virtual void setRadialFilterMinThreshold (int radial_min_threshold)=0
 

Protected Attributes

int bytes_per_pixel_ = 2
 
unsigned int frame_counter_ = 0
 
int frame_height_ = 1024
 
int frame_width_ = 1024
 
int input_scale_factor_ = 2
 
bool sensor_open_flag_
 

Detailed Description

This is input base class.

Definition at line 18 of file input_sensor.h.

Member Function Documentation

◆ closeSensor()

virtual void IInputSensor::closeSensor ( )
pure virtual

◆ configureSensor()

virtual void IInputSensor::configureSensor ( int  camera_mode)
pure virtual

◆ getExtrinsics()

virtual void IInputSensor::getExtrinsics ( CameraExtrinsics camera_extrinsics)
pure virtual

◆ getFrameCounter()

int IInputSensor::getFrameCounter ( )
inline

Get the current Frame count value.

Returns
int

Definition at line 111 of file input_sensor.h.

◆ getFrameHeight()

int IInputSensor::getFrameHeight ( )
inline

Get the Frame Height object Only integer scaling is supported.

Returns
int

Definition at line 74 of file input_sensor.h.

◆ getFrameTimestamp()

virtual bool IInputSensor::getFrameTimestamp ( ros::Time timestamp)
pure virtual

◆ getFrameWidth()

int IInputSensor::getFrameWidth ( )
inline

Get the Frame Width object Only integer scaling is supported.

Returns
int

Definition at line 65 of file input_sensor.h.

◆ getIntrinsics()

virtual void IInputSensor::getIntrinsics ( CameraIntrinsics camera_intrinsics)
pure virtual

◆ isOpened()

bool IInputSensor::isOpened ( )
inline

function to check whether input is opened

Returns
true if the input sensor opened
false if the input sensor is not opened

Definition at line 55 of file input_sensor.h.

◆ openSensor()

virtual void IInputSensor::openSensor ( std::string  sensor_name,
int  input_image_width,
int  input_image_height,
std::string  config_file_name,
std::string  input_sensor_ip 
)
pure virtual

◆ readNextFrame()

virtual bool IInputSensor::readNextFrame ( unsigned short *  depth_frame,
unsigned short *  ab_frame,
unsigned short *  conf_frame,
short *  xyz_frame 
)
pure virtual

◆ setABinvalidationThreshold()

virtual void IInputSensor::setABinvalidationThreshold ( int  threshold)
pure virtual

◆ setConfidenceThreshold()

virtual void IInputSensor::setConfidenceThreshold ( int  threshold)
pure virtual

◆ setFrameHeight()

void IInputSensor::setFrameHeight ( int  frm_height)
inline

Sett the Frame Height object Only integer scaling is supported.

Returns
int

Definition at line 93 of file input_sensor.h.

◆ setFrameWidth()

void IInputSensor::setFrameWidth ( int  frm_width)
inline

Set the Frame Width object Only integer scaling is supported.

Returns
int

Definition at line 84 of file input_sensor.h.

◆ setJBLFFilterSize()

virtual void IInputSensor::setJBLFFilterSize ( int  jblf_filter_size)
pure virtual

◆ setJBLFFilterState()

virtual void IInputSensor::setJBLFFilterState ( bool  jblf_filter_state)
pure virtual

◆ setProcessingScale()

void IInputSensor::setProcessingScale ( int  scale_factor)
inline

Set the Processing Scale object.

Parameters
scale_factor
Returns
int

Definition at line 103 of file input_sensor.h.

◆ setRadialFilterMaxThreshold()

virtual void IInputSensor::setRadialFilterMaxThreshold ( int  radial_max_threshold)
pure virtual

◆ setRadialFilterMinThreshold()

virtual void IInputSensor::setRadialFilterMinThreshold ( int  radial_min_threshold)
pure virtual

Member Data Documentation

◆ bytes_per_pixel_

int IInputSensor::bytes_per_pixel_ = 2
protected

Definition at line 28 of file input_sensor.h.

◆ frame_counter_

unsigned int IInputSensor::frame_counter_ = 0
protected

Definition at line 30 of file input_sensor.h.

◆ frame_height_

int IInputSensor::frame_height_ = 1024
protected

Definition at line 27 of file input_sensor.h.

◆ frame_width_

int IInputSensor::frame_width_ = 1024
protected

Definition at line 26 of file input_sensor.h.

◆ input_scale_factor_

int IInputSensor::input_scale_factor_ = 2
protected

Definition at line 29 of file input_sensor.h.

◆ sensor_open_flag_

bool IInputSensor::sensor_open_flag_
protected

Definition at line 25 of file input_sensor.h.


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


adi_3dtof_adtf31xx
Author(s):
autogenerated on Sat May 17 2025 02:12:30