Skip to content

Commit

Permalink
Merge pull request IntelRealSense#12 from nohayassin/AC2_merge
Browse files Browse the repository at this point in the history
AC2_release
  • Loading branch information
maloel authored Jun 2, 2020
2 parents df0f657 + abb1fa0 commit 078372f
Show file tree
Hide file tree
Showing 3 changed files with 7 additions and 7 deletions.
4 changes: 2 additions & 2 deletions src/algo/depth-to-rgb-calibration/optimizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1270,8 +1270,8 @@ void params::set_depth_resolution( size_t width, size_t height )
bool const XGA = (width == 1024 && height == 768);
if( XGA )
{
AC_LOG( DEBUG, "... changing IR threshold: " << grad_ir_threshold << " -> " << 1.5 << " (because of resolution)" );
grad_ir_threshold = 1.5;
AC_LOG( DEBUG, "... changing IR threshold: " << grad_ir_threshold << " -> " << 2.5 << " (because of resolution)" );
grad_ir_threshold = 2.5;
}
}

Expand Down
8 changes: 4 additions & 4 deletions src/algo/depth-to-rgb-calibration/optimizer.h
Original file line number Diff line number Diff line change
Expand Up @@ -112,10 +112,10 @@ namespace depth_to_rgb_calibration {
struct svm_model_linear
{
svm_model_linear();
std::vector< double > mu = { 26.451657421181550, 1.834669247710750, 3.491429858876404, 3.786071463994616, 1.267059679244040e+04, 1.739017433204909e+04, 7.950284312071314, 7.037505628020683, 1.669357700781532e+04, -4.000499638952811e+02 };
std::vector< double > sigma = { 64.543314844188930,0.399466249006394,5.051691865199965,4.838800439657138,3.560637036816310e+03,4.169466021585641e+03,3.946730380178832,2.688331347779885,9.166971780432328e+03,1.309539174549818e+03 };
std::vector< double > beta = { 0.036404266074054, 0.217416714219929, -1.448206804928638, -0.426383040511132, 0.482625970398315, -0.341211816013196, 1.476722279284806, -0.570440485581453, 0.174994874978338, -0.217118614894225 };
double bias = -0.765669809855658;
std::vector< double > mu = { 0,0,0,0,0,0,0,0,0,0 };
std::vector< double > sigma = { 1,1,1,1,1,1,1,1,1,1 };
std::vector< double > beta = { -0.00598037736275758, -0.419810195765952, -0.0519142921084610, 0.0511261823872767, -0.00326064850787589, 0.00134513193142993, -0.0305126906030304, 0, 0.000390629893900041, -0.000589640043298588 };// { 0.036404266074054, 0.217416714219929, -1.448206804928638, -0.426383040511132, 0.482625970398315, -0.341211816013196, 1.476722279284806, -0.570440485581453, 0.174994874978338, -0.217118614894225 };
double bias = 14.782481183385837;
};
struct svm_model_gaussian
{
Expand Down
2 changes: 1 addition & 1 deletion src/algo/depth-to-rgb-calibration/valid-results.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -350,7 +350,7 @@ bool optimizer::is_valid_results()
res = false;
}

bool res_svm = valid_by_svm(gaussian); //(gaussian);// (linear);
bool res_svm = valid_by_svm(linear); //(gaussian);
return (res && res_svm);
}

0 comments on commit 078372f

Please sign in to comment.