Public Member Functions | List of all members
rs2::auto_calibrated_device Class Reference

#include <rs_device.hpp>

Inheritance diagram for rs2::auto_calibrated_device:
Inheritance graph
[legend]

Public Member Functions

 auto_calibrated_device (device d)
 
calibration_table get_calibration_table ()
 
template<class T >
calibration_table run_on_chip_calibration (std::string json_content, float *health, T callback, int timeout_ms=5000) const
 
calibration_table run_on_chip_calibration (std::string json_content, float *health, int timeout_ms=5000) const
 
template<class T >
calibration_table run_tare_calibration (float ground_truth_mm, std::string json_content, T callback, int timeout_ms=5000) const
 
calibration_table run_tare_calibration (float ground_truth_mm, std::string json_content, int timeout_ms=5000) const
 
void set_calibration_table (const calibration_table &calibration)
 
- Public Member Functions inherited from rs2::calibrated_device
 calibrated_device (device d)
 
void reset_to_factory_calibration ()
 
void write_calibration () const
 
- Public Member Functions inherited from rs2::device
template<class T >
as () const
 
 device ()
 
 device (std::shared_ptr< rs2_device > dev)
 
template<class T >
first () const
 
const std::shared_ptr< rs2_device > & get () const
 
const char * get_info (rs2_camera_info info) const
 
void hardware_reset ()
 
template<class T >
bool is () const
 
 operator bool () const
 
 operator std::shared_ptr< rs2_device > ()
 
deviceoperator= (const std::shared_ptr< rs2_device > dev)
 
deviceoperator= (const device &dev)
 
std::vector< sensorquery_sensors () const
 
bool supports (rs2_camera_info info) const
 
virtual ~device ()
 

Additional Inherited Members

- Protected Attributes inherited from rs2::device
std::shared_ptr< rs2_device_dev
 

Detailed Description

Definition at line 315 of file rs_device.hpp.

Constructor & Destructor Documentation

rs2::auto_calibrated_device::auto_calibrated_device ( device  d)
inline

Definition at line 318 of file rs_device.hpp.

Member Function Documentation

calibration_table rs2::auto_calibrated_device::get_calibration_table ( )
inline

Read current calibration table from flash.

Returns
Calibration table

Definition at line 522 of file rs_device.hpp.

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

This will improve the depth noise.

Parameters
[in]json_contentJson 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 } 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 if json is nullptr it will be ignored and calibration will use the default parameters
[out]healthThe 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
[in]callbackOptional callback to get progress notifications
[in]timeout_msTimeout in ms
Returns
New calibration table

Definition at line 363 of file rs_device.hpp.

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

This will improve the depth noise.

Parameters
[in]json_contentJson 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 } 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 if json is nullptr it will be ignored and calibration will use the default parameters
[out]healthThe 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
[in]timeout_msTimeout in ms
Returns
New calibration table

Definition at line 415 of file rs_device.hpp.

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

This will adjust camera absolute distance to flat target. User needs to enter the known ground truth.

Parameters
[in]ground_truth_mmGround truth in mm must be between 60 and 10000
[in]json_contentJson string to configure tare calibration parameters: { "average step count": 20, "step count": 20, "accuracy": 2, "scan parameter": 0, "data sampling": 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 very high (0.025%) 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 if json is nullptr it will be ignored and calibration will use the default parameters
[in]content_sizeJson string size if its 0 the json will be ignored and calibration will use the default parameters
[in]callbackOptional callback to get progress notifications
[in]timeout_msTimeout in ms
Returns
New calibration table

Definition at line 457 of file rs_device.hpp.

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

This will adjust camera absolute distance to flat target. User needs to enter the known ground truth.

Parameters
[in]ground_truth_mmGround truth in mm must be between 60 and 10000
[in]json_contentJson string to configure tare calibration parameters: { "average step count": 20, "step count": 20, "accuracy": 2, "scan parameter": 0, "data sampling": 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 very high (0.025%) 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 if json is nullptr it will be ignored and calibration will use the default parameters
[in]content_sizeJson string size if its 0 the json will be ignored and calibration will use the default parameters
[in]timeout_msTimeout in ms
Returns
New calibration table

Definition at line 498 of file rs_device.hpp.

void rs2::auto_calibrated_device::set_calibration_table ( const calibration_table calibration)
inline

Set current table to dynamic area.

Parameters
[in]Calibrationtable

Definition at line 546 of file rs_device.hpp.


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


librealsense2
Author(s): Sergey Dorodnicov , Doron Hirshberg , Mark Horn , Reagan Lopez , Itay Carpis
autogenerated on Mon May 3 2021 02:50:40