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

Public Member Functions | |
| void | closeSensor () |
| closes the input file More... | |
| void | configureSensor (int camera_mode) |
| Configures the sensor. More... | |
| void | getExtrinsics (CameraExtrinsics *camera_extrinsics_data) |
| gets camera extrinsics More... | |
| bool | getFrameTimestamp (ros::Time *timestamp) |
| returns frame timestamp More... | |
| void | getIntrinsics (CameraIntrinsics *camera_intrinsics_data) |
| Gets the camera intrinsics. More... | |
| InputSensorFileRosbagBin () | |
| void | openSensor (std::string sensor_name, int input_image_width, int input_image_height, std::string config_file_name, std::string input_sensor_ip) |
| opens the bag file. More... | |
| bool | readNextFrame (unsigned short *out_depth_frame, unsigned short *out_ab_frame, unsigned short *out_conf_frame, short *out_xyz_frame) |
| reads next frame More... | |
| void | setABinvalidationThreshold (int threshold) |
| set ABinvalidation threshold More... | |
| void | setConfidenceThreshold (int threshold) |
| Set Confidence Threshold. 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 | |
| uint32_t | bytes_per_pixel_ = 2 |
| uint8_t | cam_info_buffer_ [400] |
| CameraExtrinsics | camera_extrinsics_ |
| CameraIntrinsics | camera_intrinsics_ |
| uint64_t | device_timestamp_ = 0 |
| uint32_t | frame_pitch_ = 0 |
| uint64_t | frame_timestamp_ = 0 |
| uint8_t | header_buffer_ [36] |
| uint32_t | header_version_ = 0 |
| std::ifstream | in_file_ |
| std::string | in_file_name_ |
| uint32_t | input_frame_height_ |
| uint32_t | input_frame_width_ |
| int | processing_scale_ |
| uint32_t | total_frames_ = 0 |
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 18 of file input_sensor_file_rosbagbin.h.
|
inline |
Definition at line 25 of file input_sensor_file_rosbagbin.h.
|
virtual |
closes the input file
Implements IInputSensor.
Definition at line 320 of file input_sensor_file_rosbagbin.cpp.
|
virtual |
Configures the sensor.
| camera_mode | camera mode, not used in file-io mode |
Implements IInputSensor.
Definition at line 42 of file input_sensor_file_rosbagbin.cpp.
|
virtual |
gets camera extrinsics
| camera_extrinsics_data | camera extrinsics |
Implements IInputSensor.
Definition at line 170 of file input_sensor_file_rosbagbin.cpp.
|
virtual |
returns frame timestamp
Implements IInputSensor.
Definition at line 304 of file input_sensor_file_rosbagbin.cpp.
|
virtual |
Gets the camera intrinsics.
| camera_intrinsics_data | camera intrinsics |
Implements IInputSensor.
Definition at line 159 of file input_sensor_file_rosbagbin.cpp.
|
virtual |
opens the bag file.
| sensor_name | the input bag file name |
| input_image_width | image width |
| input_image_height | image height |
| processing_scale | scales the image dimensions and camera intrinsics. |
| config_file_name | config file name of ToF SDK is not used as this is file io mode. |
Implements IInputSensor.
Definition at line 21 of file input_sensor_file_rosbagbin.cpp.
|
virtual |
reads next frame
| out_depth_frame | pointer to read depth frame |
| out_ab_frame | pointer to read ab frame |
Implements IInputSensor.
Definition at line 185 of file input_sensor_file_rosbagbin.cpp.
|
inlinevirtual |
set ABinvalidation threshold
| threshold | ABinvalidation threshold |
Implements IInputSensor.
Definition at line 80 of file input_sensor_file_rosbagbin.h.
|
inlinevirtual |
Set Confidence Threshold.
| threshold | Confidence threshold |
Implements IInputSensor.
Definition at line 91 of file input_sensor_file_rosbagbin.h.
|
inlinevirtual |
sets the size of JBLF filter
| jbfl_filter_size | parameter to set JBLF filter size |
Implements IInputSensor.
Definition at line 113 of file input_sensor_file_rosbagbin.h.
|
inlinevirtual |
sets the state of JBLF filter
| enable_jblf_filter | parameter to enable or disable JBLF filter |
Implements IInputSensor.
Definition at line 102 of file input_sensor_file_rosbagbin.h.
|
inlinevirtual |
sets the maximum threshold for radial filter
| radial_threshold_max | parameter to set maximum threshold for radial filter |
Implements IInputSensor.
Definition at line 135 of file input_sensor_file_rosbagbin.h.
|
inlinevirtual |
sets the minimum threshold for radial filter
| radial_threshold_min | parameter to set minimum threshold for radial filter |
Implements IInputSensor.
Definition at line 124 of file input_sensor_file_rosbagbin.h.
|
private |
Definition at line 151 of file input_sensor_file_rosbagbin.h.
|
private |
Definition at line 154 of file input_sensor_file_rosbagbin.h.
|
private |
Definition at line 156 of file input_sensor_file_rosbagbin.h.
|
private |
Definition at line 155 of file input_sensor_file_rosbagbin.h.
|
private |
Definition at line 149 of file input_sensor_file_rosbagbin.h.
|
private |
Definition at line 148 of file input_sensor_file_rosbagbin.h.
|
private |
Definition at line 150 of file input_sensor_file_rosbagbin.h.
|
private |
Definition at line 153 of file input_sensor_file_rosbagbin.h.
|
private |
Definition at line 147 of file input_sensor_file_rosbagbin.h.
|
private |
Definition at line 143 of file input_sensor_file_rosbagbin.h.
|
private |
Definition at line 142 of file input_sensor_file_rosbagbin.h.
|
private |
Definition at line 145 of file input_sensor_file_rosbagbin.h.
|
private |
Definition at line 144 of file input_sensor_file_rosbagbin.h.
|
private |
Definition at line 146 of file input_sensor_file_rosbagbin.h.
|
private |
Definition at line 152 of file input_sensor_file_rosbagbin.h.