Class auto_calibrated_device

Inheritance Relationships

Base Type

Class Documentation

class auto_calibrated_device : public rs2::calibrated_device

Public Functions

inline auto_calibrated_device(device d)
template<class T>
inline calibration_table run_on_chip_calibration(std::string json_content, float *health, T callback, int timeout_ms = 5000) const

On-chip calibration intended to reduce the Depth noise. Applies to D400 Depth cameras

Parameters:
  • json_content[in] Json string to configure regular speed on chip calibration parameters: { “calib type” : 0, “speed”: 3, “scan parameter”: 0, “adjust both sides”: 0, “white wall mode”: 0, “host assistance”: 0 } calib_type - calibraton type: 0 = regular, 1 = focal length, 2 = both regular and focal length in order speed - for regular calibration. value can be one of: Very fast = 0, Fast = 1, Medium = 2, Slow = 3, White wall = 4, default is Slow for type 0 and Fast for type 2 scan_parameter - for regular calibration. value can be one of: Py scan (default) = 0, Rx scan = 1 adjust_both_sides - for focal length calibration. value can be one of: 0 = adjust right only, 1 = adjust both sides white_wall_mode - white wall mode: 0 for normal mode and 1 for white wall mode host_assistance: 0 for no assistance, 1 for starting with assistance, 2 for first part feeding host data to firmware, 3 for second part of feeding host data to firmware (calib_type 2 only) if json is nullptr it will be ignored and calibration will use the default parameters

  • health[out] The absolute value of regular calibration Health-Check captures how far camera calibration is from the optimal one [0, 0.25) - Good [0.25, 0.75) - Can be Improved [0.75, ) - Requires Calibration The absolute value of focal length calibration Health-Check captures how far camera calibration is from the optimal one [0, 0.15) - Good [0.15, 0.75) - Can be Improved [0.75, ) - Requires Calibration The two health numbers are encoded in one integer as follows for calib_type 2: Regular health number times 1000 are bits 0 to 11 Regular health number is negative if bit 24 is 1 Focal length health number times 1000 are bits 12 to 23 Focal length health number is negative if bit 25 is 1

  • callback[in] Optional callback to get progress notifications

  • timeout_ms[in] Timeout in ms

Returns:

New calibration table

inline calibration_table run_on_chip_calibration(std::string json_content, float *health, int timeout_ms = 5000) const

On-chip calibration intended to reduce the Depth noise. Applies to D400 Depth cameras

Parameters:
  • json_content[in] Json string to configure regular speed on chip calibration parameters: { “focal length” : 0, “speed”: 3, “scan parameter”: 0, “adjust both sides”: 0, “white wall mode”: 0, “host assistance”: 0 } focal_length - calibraton type: 0 = regular, 1 = focal length, 2 = both regular and focal length in order speed - for regular calibration. value can be one of: Very fast = 0, Fast = 1, Medium = 2, Slow = 3, White wall = 4, default is Slow for type 0 and Fast for type 2 scan_parameter - for regular calibration. value can be one of: Py scan (default) = 0, Rx scan = 1 adjust_both_sides - for focal length calibration. value can be one of: 0 = adjust right only, 1 = adjust both sides white_wall_mode - white wall mode: 0 for normal mode and 1 for white wall mode host_assistance: 0 for no assistance, 1 for starting with assistance, 2 for first part feeding host data to firmware, 3 for second part of feeding host data to firmware (calib_type 2 only) if json is nullptr it will be ignored and calibration will use the default parameters

  • health[out] The absolute value of regular calibration Health-Check captures how far camera calibration is from the optimal one [0, 0.25) - Good [0.25, 0.75) - Can be Improved [0.75, ) - Requires Calibration The absolute value of focal length calibration Health-Check captures how far camera calibration is from the optimal one [0, 0.15) - Good [0.15, 0.75) - Can be Improved [0.75, ) - Requires Calibration The two health numbers are encoded in one integer as follows for calib_type 2: Regular health number times 1000 are bits 0 to 11 Regular health number is negative if bit 24 is 1 Focal length health number times 1000 are bits 12 to 23 Focal length health number is negative if bit 25 is 1

  • timeout_ms[in] Timeout in ms

Returns:

New calibration table

template<class T>
inline calibration_table run_tare_calibration(float ground_truth_mm, std::string json_content, float *health, T callback, int timeout_ms = 5000) const

Tare calibration adjusts the camera absolute distance to flat target. Applies to D400 Depth cameras User needs to enter the known ground truth.

Parameters:
  • ground_truth_mm[in] Ground truth in mm must be between 60 and 10000

  • json_content[in] Json string to configure tare calibration parameters: { “average step count”: 20, “step count”: 20, “accuracy”: 2, “scan parameter”: 0, “data sampling”: 0, “host assistance”: 0, “depth” : 0 } average step count - number of frames to average, must be between 1 - 30, default = 20 step count - max iteration steps, must be between 5 - 30, default = 10 accuracy - Subpixel accuracy level, value can be one of: Very high = 0 (0.025%), High = 1 (0.05%), Medium = 2 (0.1%), Low = 3 (0.2%), Default = Very high (0.025%), default is Medium scan_parameter - value can be one of: Py scan (default) = 0, Rx scan = 1 data_sampling - value can be one of:polling data sampling = 0, interrupt data sampling = 1 host_assistance: 0 for no assistance, 1 for starting with assistance, 2 for feeding host data to firmware depth: 0 for not relating to depth, > 0 for feeding depth from host to firmware, -1 for ending to feed depth from host to firmware if json is nullptr it will be ignored and calibration will use the default parameters

  • content_size[in] Json string size if its 0 the json will be ignored and calibration will use the default parameters

  • health[out] The absolute value of regular calibration Health-Check captures how far camera calibration is from the optimal one [0, 0.25) - Good [0.25, 0.75) - Can be Improved [0.75, ) - Requires Calibration

  • callback[in] Optional callback to get progress notifications

  • timeout_ms[in] Timeout in ms

Returns:

New calibration table

inline calibration_table run_tare_calibration(float ground_truth_mm, std::string json_content, float *health, int timeout_ms = 5000) const

Tare calibration adjusts the camera absolute distance to flat target. Applies to D400 Depth cameras User needs to enter the known ground truth.

Parameters:
  • ground_truth_mm[in] Ground truth in mm must be between 60 and 10000

  • json_content[in] Json string to configure tare calibration parameters: { “average step count”: 20, “step count”: 20, “accuracy”: 2, “scan parameter”: 0, “data sampling”: 0, “host assistance”: 0, “depth” : 0 } average step count - number of frames to average, must be between 1 - 30, default = 20 step count - max iteration steps, must be between 5 - 30, default = 10 accuracy - Subpixel accuracy level, value can be one of: Very high = 0 (0.025%), High = 1 (0.05%), Medium = 2 (0.1%), Low = 3 (0.2%), Default = Very high (0.025%), default is Medium scan_parameter - value can be one of: Py scan (default) = 0, Rx scan = 1 data_sampling - value can be one of:polling data sampling = 0, interrupt data sampling = 1 host_assistance: 0 for no assistance, 1 for starting with assistance, 2 for feeding host data to firmware depth: 0 for not relating to depth, > 0 for feeding depth from host to firmware, -1 for ending to feed depth from host to firmware if json is nullptr it will be ignored and calibration will use the default parameters

  • content_size[in] Json string size if its 0 the json will be ignored and calibration will use the default parameters

  • health[out] The absolute value of regular calibration Health-Check captures how far camera calibration is from the optimal one [0, 0.25) - Good [0.25, 0.75) - Can be Improved [0.75, ) - Requires Calibration

  • timeout_ms[in] Timeout in ms

Returns:

New calibration table

template<class T>
inline calibration_table process_calibration_frame(rs2::frame f, float *const health, T callback, int timeout_ms = 5000) const

When doing a host-assited calibration (Tare or on-chip) add frame to the calibration process

Parameters:
  • f[in] The next depth frame.

  • callback[in] Optional callback to get progress notifications

  • timeout_ms[in] Timeout in ms

  • health[out] The health check numbers before and after calibration

Returns:

a New calibration table when process is done. An empty table otherwise - need more frames.

inline calibration_table process_calibration_frame(rs2::frame f, float *const health, int timeout_ms = 5000) const

When doing a host-assited calibration (Tare or on-chip) add frame to the calibration process

Parameters:
  • f[in] The next depth frame.

  • timeout_ms[in] Timeout in ms

  • health[out] The health check numbers before and after calibration

Returns:

a New calibration table when process is done. An empty table otherwise - need more frames.

inline calibration_table get_calibration_table()

Read current calibration table from flash.

Returns:

Calibration table

inline void set_calibration_table(const calibration_table &calibration)

Set current table to dynamic area.

Parameters:

Calibration[in] table

inline std::vector<uint8_t> run_focal_length_calibration(rs2::frame_queue left, rs2::frame_queue right, float target_w, float target_h, int adjust_both_sides, float *ratio, float *angle) const

Run target-based focal length calibration for D400 Stereo Cameras

Parameters:
  • left_queue[in] container for left IR frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI.

  • right_queue[in] container for right IR frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI

  • target_w[in] the rectangle width in mm on the target

  • target_h[in] the rectangle height in mm on the target

  • adjust_both_sides[in] 1 for adjusting both left and right camera calibration tables and 0 for adjusting right camera calibraion table only

  • ratio[out] the corrected ratio from the calibration

  • angle[out] the target’s tilt angle

Returns:

New calibration table

template<class T>
inline std::vector<uint8_t> run_focal_length_calibration(rs2::frame_queue left, rs2::frame_queue right, float target_w, float target_h, int adjust_both_sides, float *ratio, float *angle, T callback) const

Run target-based focal length calibration for D400 Stereo Cameras

Parameters:
  • left_queue[in] container for left IR frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI.

  • right_queue[in] container for right IR frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI

  • target_w[in] the rectangle width in mm on the target

  • target_h[in] the rectangle height in mm on the target

  • adjust_both_sides[in] 1 for adjusting both left and right camera calibration tables and 0 for adjusting right camera calibraion table only

  • ratio[out] the corrected ratio from the calibration

  • angle[out] the target’s tilt angle

Returns:

New calibration table

inline std::vector<uint8_t> run_uv_map_calibration(rs2::frame_queue left, rs2::frame_queue color, rs2::frame_queue depth, int py_px_only, float *health, int health_size) const

Depth-RGB UV-Map calibration. Applicable for D400 cameras

Parameters:
  • left[in] container for left IR frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI.

  • color[in] container for RGB frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI

  • depth[in] container for Depth frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI

  • py_px_only[in] 1 for calibrating color camera py and px only, 1 for calibrating color camera py, px, fy, and fx.

  • health[out] The four health check numbers int the oorder of px, py, fx, fy for the calibration

  • health_size[in] number of health check numbers, which is 4 by default

  • callback[in] Optional callback for update progress notifications, the progress value is normailzed to 1

Returns:

New calibration table

template<class T>
inline std::vector<uint8_t> run_uv_map_calibration(rs2::frame_queue left, rs2::frame_queue color, rs2::frame_queue depth, int py_px_only, float *health, int health_size, T callback) const

Depth-RGB UV-Map calibration. Applicable for D400 cameras

Parameters:
  • left[in] container for left IR frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI.

  • color[in] container for RGB frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI

  • depth[in] container for Depth frames with resoluton of 1280x720 and the target in the center of 320x240 pixels ROI

  • py_px_only[in] 1 for calibrating color camera py and px only, 1 for calibrating color camera py, px, fy, and fx.

  • health[out] The four health check numbers in order of px, py, fx, fy for the calibration

  • health_size[in] number of health check numbers, which is 4 by default

  • callback[in] Optional callback for update progress notifications, the progress value is normailzed to 1

  • client_data[in] Optional client data for the callback

Returns:

New calibration table

inline float calculate_target_z(rs2::frame_queue queue1, rs2::frame_queue queue2, rs2::frame_queue queue3, float target_width, float target_height) const

Calculate Z for calibration target - distance to the target’s plane

Parameters:
  • queue1-3[in] Frame queues of raw images used to calculate and extract the distance to a predefined target pattern. For D400 the indexes 1-3 correspond to Left IR, Right IR and Depth with only the Left IR being used

  • target_width[in] expected target’s horizontal dimension in mm

  • target_height[in] expected target’s vertical dimension in mm

Returns:

Calculated distance (Z) to target in millimeter, return negative number on failure

template<class T>
inline float calculate_target_z(rs2::frame_queue queue1, rs2::frame_queue queue2, rs2::frame_queue queue3, float target_width, float target_height, T callback) const

Calculate Z for calibration target - distance to the target’s plane

Parameters:
  • queue1-3[in] Frame queues of raw images used to calculate and extract the distance to a predefined target pattern. For D400 the indexes 1-3 correspond to Left IR, Right IR and Depth with only the Left IR being used

  • target_width[in] expected target’s horizontal dimension in mm

  • target_height[in] expected target’s vertical dimension in mm

  • callback[in] Optional callback for reporting progress status

Returns:

Calculated distance (Z) to target in millimeter, return negative number on failure