Public Member Functions | Public Attributes | List of all members
librealsense::algo::depth_to_rgb_calibration::params Struct Reference

#include <optimizer.h>

Public Member Functions

 params ()
 
void set_depth_resolution (size_t width, size_t height, rs2_digital_gain digital_gain)
 
void set_rgb_resolution (size_t width, size_t height)
 

Public Attributes

double alpha = (double)1 / (double)3
 
double constant_weights = 1000
 
double control_param = 0.5
 
size_t dilation_size = 1
 
double dir_std_th [N_BASIC_DIRECTIONS] = { 0.09, 0.09, 0.09, 0.09 }
 
double edge_distribution_min_max_ratio = 0.005
 
double edge_thresh4_logic_lum = 0.1
 
double edges_per_direction_ratio_th = 0.004
 
double gamma = 0.9
 
size_t gause_kernel_size = 5
 
double gauss_sigma = 1
 
double grad_dir_ratio = 10
 
double grad_dir_ratio_prep = 1.5
 
double grad_ir_high_th = 2.5
 
double grad_ir_low_th = std::numeric_limits<double>::max()
 
double grad_ir_threshold = 3.5
 
double grad_z_high_th = std::numeric_limits<double>::max()
 
double grad_z_low_th = 0
 
double grad_z_max = 1000
 
double grad_z_min = 25
 
int grad_z_threshold = 0
 
int max_back_track_iters = 50
 
double max_global_los_scaling_step = 0.004
 
double const max_K2DSM_iters = 10
 
int max_optimization_iters = 50
 
double const max_scaling_step = 0.020000000000000
 
double max_step_size = 1
 
double max_sub_mm_z = 4
 
double max_xy_movement_from_origin
 
double max_xy_movement_per_calibration [3]
 
double min_cost_delta = 1
 
double min_rgb_mat_delta = 0.00001
 
int min_section_with_enough_edges = 2
 
double min_step_size = 0.00001
 
double min_weighted_edge_per_section_depth = 0
 
double min_weighted_edge_per_section_rgb = 0
 
int minimal_full_directions = 2
 
double move_last_success_thresh_pix_num = 0
 
double const move_last_success_thresh_pix_val = 25
 
double const move_thresh_pix_val = 20
 
double move_threshold_pix_num = 0
 
p_matrix normalize_mat
 
size_t num_of_sections_for_edge_distribution_x = 2
 
size_t num_of_sections_for_edge_distribution_y = 2
 
double pix_per_section_depth_th = 0.01
 
double pix_per_section_rgb_th = 0.01
 
bool require_orthogonal_valid_dirs = false
 
double saturation_ratio_th = 0.05
 
int saturation_value = 230
 
double tau = 0.5
 
bool use_enhanced_preprocessing = true
 

Detailed Description

Definition at line 30 of file optimizer.h.

Constructor & Destructor Documentation

params::params ( )

Definition at line 1532 of file optimizer.cpp.

Member Function Documentation

void params::set_depth_resolution ( size_t  width,
size_t  height,
rs2_digital_gain  digital_gain 
)

Definition at line 1556 of file optimizer.cpp.

void params::set_rgb_resolution ( size_t  width,
size_t  height 
)

Definition at line 1615 of file optimizer.cpp.

Member Data Documentation

double librealsense::algo::depth_to_rgb_calibration::params::alpha = (double)1 / (double)3

Definition at line 37 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::constant_weights = 1000

Definition at line 77 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::control_param = 0.5

Definition at line 52 of file optimizer.h.

size_t librealsense::algo::depth_to_rgb_calibration::params::dilation_size = 1

Definition at line 67 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::dir_std_th[N_BASIC_DIRECTIONS] = { 0.09, 0.09, 0.09, 0.09 }

Definition at line 90 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::edge_distribution_min_max_ratio = 0.005

Definition at line 64 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::edge_thresh4_logic_lum = 0.1

Definition at line 42 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::edges_per_direction_ratio_th = 0.004

Definition at line 89 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::gamma = 0.9

Definition at line 36 of file optimizer.h.

size_t librealsense::algo::depth_to_rgb_calibration::params::gause_kernel_size = 5

Definition at line 69 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::gauss_sigma = 1

Definition at line 68 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::grad_dir_ratio = 10

Definition at line 65 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::grad_dir_ratio_prep = 1.5

Definition at line 66 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::grad_ir_high_th = 2.5

Definition at line 46 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::grad_ir_low_th = std::numeric_limits<double>::max()

Definition at line 45 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::grad_ir_threshold = 3.5

Definition at line 38 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::grad_z_high_th = std::numeric_limits<double>::max()

Definition at line 48 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::grad_z_low_th = 0

Definition at line 47 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::grad_z_max = 1000

Definition at line 41 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::grad_z_min = 25

Definition at line 40 of file optimizer.h.

int librealsense::algo::depth_to_rgb_calibration::params::grad_z_threshold = 0

Definition at line 39 of file optimizer.h.

int librealsense::algo::depth_to_rgb_calibration::params::max_back_track_iters = 50

Definition at line 53 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::max_global_los_scaling_step = 0.004

Definition at line 86 of file optimizer.h.

double const librealsense::algo::depth_to_rgb_calibration::params::max_K2DSM_iters = 10

Definition at line 83 of file optimizer.h.

int librealsense::algo::depth_to_rgb_calibration::params::max_optimization_iters = 50

Definition at line 54 of file optimizer.h.

double const librealsense::algo::depth_to_rgb_calibration::params::max_scaling_step = 0.020000000000000

Definition at line 82 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::max_step_size = 1

Definition at line 50 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::max_sub_mm_z = 4

Definition at line 76 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::max_xy_movement_from_origin

Definition at line 81 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::max_xy_movement_per_calibration[3]

Definition at line 80 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::min_cost_delta = 1

Definition at line 56 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::min_rgb_mat_delta = 0.00001

Definition at line 55 of file optimizer.h.

int librealsense::algo::depth_to_rgb_calibration::params::min_section_with_enough_edges = 2

Definition at line 97 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::min_step_size = 0.00001

Definition at line 51 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::min_weighted_edge_per_section_depth = 0

Definition at line 58 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::min_weighted_edge_per_section_rgb = 0

Definition at line 59 of file optimizer.h.

int librealsense::algo::depth_to_rgb_calibration::params::minimal_full_directions = 2

Definition at line 91 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::move_last_success_thresh_pix_num = 0

Definition at line 73 of file optimizer.h.

double const librealsense::algo::depth_to_rgb_calibration::params::move_last_success_thresh_pix_val = 25

Definition at line 72 of file optimizer.h.

double const librealsense::algo::depth_to_rgb_calibration::params::move_thresh_pix_val = 20

Definition at line 70 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::move_threshold_pix_num = 0

Definition at line 71 of file optimizer.h.

p_matrix librealsense::algo::depth_to_rgb_calibration::params::normalize_mat

Definition at line 62 of file optimizer.h.

size_t librealsense::algo::depth_to_rgb_calibration::params::num_of_sections_for_edge_distribution_x = 2

Definition at line 60 of file optimizer.h.

size_t librealsense::algo::depth_to_rgb_calibration::params::num_of_sections_for_edge_distribution_y = 2

Definition at line 61 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::pix_per_section_depth_th = 0.01

Definition at line 96 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::pix_per_section_rgb_th = 0.01

Definition at line 95 of file optimizer.h.

bool librealsense::algo::depth_to_rgb_calibration::params::require_orthogonal_valid_dirs = false

Definition at line 92 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::saturation_ratio_th = 0.05

Definition at line 94 of file optimizer.h.

int librealsense::algo::depth_to_rgb_calibration::params::saturation_value = 230

Definition at line 93 of file optimizer.h.

double librealsense::algo::depth_to_rgb_calibration::params::tau = 0.5

Definition at line 57 of file optimizer.h.

bool librealsense::algo::depth_to_rgb_calibration::params::use_enhanced_preprocessing = true

Definition at line 99 of file optimizer.h.


The documentation for this struct was generated from the following files:


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