input_sensor.h
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c), 2023 - Analog Devices Inc. All Rights Reserved.
3 This software is PROPRIETARY & CONFIDENTIAL to Analog Devices, Inc.
4 and its licensors.
5 ******************************************************************************/
6 
7 #ifndef INPUT_SENSOR_H
8 #define INPUT_SENSOR_H
9 
10 #include <ros/ros.h>
11 #include <stdint.h>
12 #include "adi_camera.h"
13 
19 {
20 protected:
21  bool sensor_open_flag_;
22  int frame_width_ = 1024;
23  int frame_height_ = 1024;
24  int bytes_per_pixel_ = 2;
26  unsigned int frame_counter_ = 0;
27 
28 public:
29  virtual void openSensor(std::string sensor_name, int input_image_width, int input_image_height,
30  std::string config_file_name, std::string input_sensor_ip) = 0;
31  virtual void configureSensor(int camera_mode) = 0;
32  virtual void getIntrinsics(CameraIntrinsics* camera_intrinsics) = 0;
33  virtual void getExtrinsics(CameraExtrinsics* camera_extrinsics) = 0;
34  virtual bool readNextFrame(unsigned short* depth_frame, unsigned short* ab_frame, unsigned short* conf_frame,
35  short* xyz_frame) = 0;
36  virtual bool getFrameTimestamp(ros::Time* timestamp) = 0;
37  virtual void closeSensor() = 0;
38  virtual void setConfidenceThreshold(int threshold) = 0;
39  virtual void setABinvalidationThreshold(int threshold) = 0;
40  virtual void setJBLFFilterState(bool jblf_filter_state) = 0;
41  virtual void setJBLFFilterSize(int jblf_filter_size) = 0;
42  virtual void setRadialFilterMinThreshold(int radial_min_threshold) = 0;
43  virtual void setRadialFilterMaxThreshold(int radial_max_threshold) = 0;
44 
51  bool isOpened()
52  {
53  return sensor_open_flag_;
54  }
61  int getFrameWidth()
62  {
63  return frame_width_;
64  }
70  int getFrameHeight()
71  {
72  return frame_height_;
73  }
80  void setFrameWidth(int frm_width)
81  {
82  frame_width_ = frm_width;
83  }
89  void setFrameHeight(int frm_height)
90  {
91  frame_height_ = frm_height;
92  }
99  void setProcessingScale(int scale_factor)
100  {
101  input_scale_factor_ = scale_factor;
102  }
107  int getFrameCounter()
108  {
109  return frame_counter_;
110  }
111 };
112 
113 #endif
IInputSensor::getFrameCounter
int getFrameCounter()
Get the current Frame count value.
Definition: input_sensor.h:111
IInputSensor::getFrameTimestamp
virtual bool getFrameTimestamp(ros::Time *timestamp)=0
IInputSensor::setABinvalidationThreshold
virtual void setABinvalidationThreshold(int threshold)=0
IInputSensor::setFrameWidth
void setFrameWidth(int frm_width)
Set the Frame Width object Only integer scaling is supported.
Definition: input_sensor.h:84
ros.h
IInputSensor::frame_width_
int frame_width_
Definition: input_sensor.h:26
IInputSensor::bytes_per_pixel_
int bytes_per_pixel_
Definition: input_sensor.h:28
IInputSensor::setRadialFilterMinThreshold
virtual void setRadialFilterMinThreshold(int radial_min_threshold)=0
IInputSensor::configureSensor
virtual void configureSensor(int camera_mode)=0
IInputSensor::setConfidenceThreshold
virtual void setConfidenceThreshold(int threshold)=0
IInputSensor::getFrameHeight
int getFrameHeight()
Get the Frame Height object Only integer scaling is supported.
Definition: input_sensor.h:74
IInputSensor::setJBLFFilterSize
virtual void setJBLFFilterSize(int jblf_filter_size)=0
IInputSensor::frame_counter_
unsigned int frame_counter_
Definition: input_sensor.h:30
IInputSensor
This is input base class.
Definition: input_sensor.h:18
IInputSensor::input_scale_factor_
int input_scale_factor_
Definition: input_sensor.h:29
IInputSensor::getExtrinsics
virtual void getExtrinsics(CameraExtrinsics *camera_extrinsics)=0
adi_camera.h
IInputSensor::readNextFrame
virtual bool readNextFrame(unsigned short *depth_frame, unsigned short *ab_frame, unsigned short *conf_frame, short *xyz_frame)=0
IInputSensor::openSensor
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
IInputSensor::getFrameWidth
int getFrameWidth()
Get the Frame Width object Only integer scaling is supported.
Definition: input_sensor.h:65
IInputSensor::setFrameHeight
void setFrameHeight(int frm_height)
Sett the Frame Height object Only integer scaling is supported.
Definition: input_sensor.h:93
IInputSensor::setProcessingScale
void setProcessingScale(int scale_factor)
Set the Processing Scale object.
Definition: input_sensor.h:103
ros::Time
CameraExtrinsics
Extrinsic parameters of the camera.
Definition: adi_camera.h:38
CameraIntrinsics
Intrinsic parameters of the camera.
Definition: adi_camera.h:15
IInputSensor::frame_height_
int frame_height_
Definition: input_sensor.h:27
IInputSensor::sensor_open_flag_
bool sensor_open_flag_
Definition: input_sensor.h:25
IInputSensor::setRadialFilterMaxThreshold
virtual void setRadialFilterMaxThreshold(int radial_max_threshold)=0
IInputSensor::setJBLFFilterState
virtual void setJBLFFilterState(bool jblf_filter_state)=0
IInputSensor::getIntrinsics
virtual void getIntrinsics(CameraIntrinsics *camera_intrinsics)=0
IInputSensor::closeSensor
virtual void closeSensor()=0
IInputSensor::isOpened
bool isOpened()
function to check whether input is opened
Definition: input_sensor.h:55


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