This is input class for sensor as camera. More...
#include <input_sensor_adtf31xx.h>

Public Member Functions | |
| void | closeSensor () |
| closes the sensor More... | |
| void | configureSensor (int camera_mode) |
| Configures the camera. More... | |
| void | getExtrinsics (CameraExtrinsics *camera_extrinsics) |
| Gets camera extrinsics. More... | |
| bool | getFrameTimestamp (ros::Time *timestamp) |
| gets the frame timestamp from ToF SDK More... | |
| void | getIntrinsics (CameraIntrinsics *camera_intrinsics) |
| gets the camera intrinsics from the ToF SDK. More... | |
| void | openSensor (std::string, int input_image_width, int input_image_height, std::string config_file_name, std::string input_sensor_ip) |
| Opens the camera. More... | |
| bool | readNextFrame (unsigned short *depth_frame, unsigned short *ab_frame, unsigned short *conf_frame, short *xyz_frame) |
| reads frame from ToF SDK More... | |
| void | setABinvalidationThreshold (int threshold) |
| calls set ab invalidation threshold function from ToF SDK More... | |
| void | setConfidenceThreshold (int threshold) |
| calls set confidence threshold function from ToF SDK More... | |
| void | setJBLFFilterSize (int jbfl_filter_size) |
| sets the size of JBLF filter More... | |
| void | setJBLFFilterState (bool enable_jblf_filter) |
| sets the state of JBLF filter More... | |
| void | setRadialFilterMaxThreshold (int radial_max_threshold) |
| sets the maximum threshold for radial filter More... | |
| void | setRadialFilterMinThreshold (int radial_min_threshold) |
| sets the minimum threshold for radial filter More... | |
Public Member Functions inherited from IInputSensor | |
| int | getFrameCounter () |
| Get the current Frame count value. More... | |
| int | getFrameHeight () |
| Get the Frame Height object Only integer scaling is supported. More... | |
| int | getFrameWidth () |
| Get the Frame Width object Only integer scaling is supported. More... | |
| bool | isOpened () |
| function to check whether input is opened More... | |
| 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... | |
| void | setProcessingScale (int scale_factor) |
| Set the Processing Scale object. More... | |
Private Attributes | |
| std::shared_ptr< aditof::Camera > | camera_ |
| CameraIntrinsics | camera_intrinsics_ |
Additional Inherited Members | |
Protected Attributes inherited from IInputSensor | |
| 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_ |
This is input class for sensor as camera.
Definition at line 20 of file input_sensor_adtf31xx.h.
|
virtual |
closes the sensor
Implements IInputSensor.
Definition at line 293 of file input_sensor_adtf31xx.cpp.
|
virtual |
Configures the camera.
| camera_mode | camera_mode |
Implements IInputSensor.
Definition at line 79 of file input_sensor_adtf31xx.cpp.
|
virtual |
Gets camera extrinsics.
| camera_extrinsics | Camera extrinsics |
Implements IInputSensor.
Definition at line 270 of file input_sensor_adtf31xx.cpp.
|
virtual |
gets the frame timestamp from ToF SDK
Implements IInputSensor.
Definition at line 258 of file input_sensor_adtf31xx.cpp.
|
virtual |
gets the camera intrinsics from the ToF SDK.
| camera_intrinsics | camera intrinsics of ToF module. |
Implements IInputSensor.
Definition at line 172 of file input_sensor_adtf31xx.cpp.
|
virtual |
Opens the camera.
| sensor_name | This parameter is not used in this derived member function. |
| input_image_width | width of the image |
| input_image_height | height of the image |
| processing_scale | scale factor for image and camera intrinsics |
| config_file_name | path of configuration json file for ToF SDK. |
Implements IInputSensor.
Definition at line 28 of file input_sensor_adtf31xx.cpp.
|
virtual |
reads frame from ToF SDK
| depth_frame | pointer to get depth frame |
| ab_frame | pointer to get ab frame |
Implements IInputSensor.
Definition at line 194 of file input_sensor_adtf31xx.cpp.
|
virtual |
calls set ab invalidation threshold function from ToF SDK
| threshold | abinvalidation threshold |
Implements IInputSensor.
Definition at line 305 of file input_sensor_adtf31xx.cpp.
|
virtual |
calls set confidence threshold function from ToF SDK
| threshold | confidence threshold |
Implements IInputSensor.
Definition at line 316 of file input_sensor_adtf31xx.cpp.
|
virtual |
sets the size of JBLF filter
| jbfl_filter_size | parameter to set JBLF filter size |
Implements IInputSensor.
Definition at line 338 of file input_sensor_adtf31xx.cpp.
|
virtual |
sets the state of JBLF filter
| enable_jblf_filter | parameter to enable or disable JBLF filter |
Implements IInputSensor.
Definition at line 327 of file input_sensor_adtf31xx.cpp.
|
virtual |
sets the maximum threshold for radial filter
| radial_threshold_max | parameter to set maximum threshold for radial filter |
Implements IInputSensor.
Definition at line 360 of file input_sensor_adtf31xx.cpp.
|
virtual |
sets the minimum threshold for radial filter
| radial_threshold_min | parameter to set minimum threshold for radial filter |
Implements IInputSensor.
Definition at line 349 of file input_sensor_adtf31xx.cpp.
|
private |
Definition at line 44 of file input_sensor_adtf31xx.h.
|
private |
Definition at line 45 of file input_sensor_adtf31xx.h.