31 #include <mrpt/otherlibs/do_opencv_includes.h> 43 #ifdef MRPT_OS_WINDOWS 71 CvPoint min_point,max_point;
73 bool entireImg = (x_search_ini<0 || y_search_ini<0 || x_search_size<0 || y_search_size<0);
92 const int patch_w = patch_im.
getWidth();
97 x_search_size = im_w - patch_w;
98 y_search_size = im_h - patch_h;
102 if ((x_search_ini + x_search_size + patch_w)>im_w)
103 x_search_size -= (x_search_ini + x_search_size + patch_w) - im_w;
105 if ((y_search_ini + y_search_size + patch_h)>im_h)
106 y_search_size -= (y_search_ini + y_search_size + patch_h) - im_h;
108 ASSERT_( (x_search_ini + x_search_size + patch_w)<=im_w )
109 ASSERT_( (y_search_ini + y_search_size + patch_h)<=im_h )
111 IplImage *result = cvCreateImage(cvSize(x_search_size+1,y_search_size+1),IPL_DEPTH_32F, 1);
113 CImage img_region_to_search;
123 img_region_to_search,
126 patch_w+x_search_size,
127 patch_h+y_search_size
133 img_region_to_search.
getAs<IplImage>(),
134 patch_im.
getAs<IplImage>(),
140 cvMinMaxLoc(result,&mini,&max_val,&min_point,&max_point,NULL);
145 cvReleaseImage( &result );
148 THROW_EXCEPTION(
"The MRPT has been compiled with MRPT_HAS_OPENCV=0 !");
163 cvFlip(
img.getAs<IplImage>());
164 img.setOriginTopLeft(
true);
166 THROW_EXCEPTION(
"The MRPT has been compiled with MRPT_HAS_OPENCV=0 !");
182 res.x = xy.
x - A.get_unsafe(0,2);
183 res.y = xy.
y - A.get_unsafe(1,2);
184 res.z = A.get_unsafe(0,0);
187 const double u =
res.norm();
198 const double focalLengthX,
199 const double focalLengthY,
200 const double centerX,
201 const double centerY)
205 A(0,0) = focalLengthX;
206 A(1,1) = focalLengthY;
219 unsigned int camIndex,
229 fx=0.79345f; fy=1.05793f;
230 cx=0.55662f; cy=0.52692f;
235 fx=0.95666094f; fy=1.3983423f;
236 cx=0.54626328f; cy=0.4939191f;
246 resX * cx, resY * cy );
257 float lx = 0.0, ly = 0.0;
260 for( itList1 = feat_list.
begin(); itList1 != feat_list.
end(); itList1++)
264 for( itList2 = itList1; itList2 != feat_list.
end(); itList2++)
266 if( (lx == (*itList2)->x && ly == (*itList2)->y ) && ( (*itList2)->x > 0.0f && (*itList2)->y > 0.0f ))
268 (*itList2)->x = -1.0f;
269 (*itList2)->y = -1.0f;
275 for( itList1 = feat_list.
begin(); itList1 != feat_list.
end();)
277 if( (*itList1)->x == -1.0f && (*itList1)->y == -1.0f )
278 itList1 = feat_list.
erase( itList1 );
295 std::cout << std::endl <<
"[ROW CHECKING]------------------------------------------" << std::endl;
298 for( itLeft = leftList.
begin(), itRight = rightList.
begin(); itLeft != leftList.
end(); )
300 if( (*itLeft)->x < 0 || (*itLeft)->y < 0 ||
301 (*itRight)->x < 0 || (*itRight)->y < 0 ||
302 fabs( (*itLeft)->y - (*itRight)->y ) > threshold )
304 std::cout <<
"[Erased Feature] Row Dif: " << fabs( (*itLeft)->y - (*itRight)->y ) << std::endl;
305 itLeft = leftList.
erase( itLeft );
306 itRight = rightList.
erase( itRight );
315 std::cout <<
"------------------------------------------" << std::endl;
317 std::cout <<
"Tracked features: " << leftList.
size() <<
" and " << rightList.
size() << std::endl;
334 double varx = 0, vary = 0;
336 for( it = list.
begin(); it != list.
end(); it++ )
344 for( it = list.
begin(); it != list.
end(); it++ )
352 std[0] = sqrt( varx );
353 std[1] = sqrt( vary );
369 for( it = feat_list.begin(); it != feat_list.end(); it++ )
371 err.
x = it->other_x - (it->this_x*mat.get_unsafe(0,0) + it->this_y*mat.get_unsafe(0,1) + it->this_z*mat.get_unsafe(0,2) + Rt.
x());
372 err.
y = it->other_y - (it->this_x*mat.get_unsafe(1,0) + it->this_y*mat.get_unsafe(1,1) + it->this_z*mat.get_unsafe(1,2) + Rt.
y());
373 err.
z = it->other_z - (it->this_x*mat.get_unsafe(2,0) + it->this_y*mat.get_unsafe(2,1) + it->this_z*mat.get_unsafe(2,2) + Rt.z());
378 return( acum/feat_list.size() );
394 if( itLand1->ID == itLand2->ID )
399 pair.
this_x = itLand1->pose_mean.x;
400 pair.
this_y = itLand1->pose_mean.y;
401 pair.
this_z = itLand1->pose_mean.z;
403 pair.
other_x = itLand2->pose_mean.x;
404 pair.
other_y = itLand2->pose_mean.y;
405 pair.
other_z = itLand2->pose_mean.z;
407 outList.push_back( pair );
421 if( (
int(
x)-1 >= 0 ) && (
int(
y)-1 >= 0 ) && (
x+1 <
image.getWidth() ) && (
y+1 <
image.getHeight() ) )
443 nim.resize(
image.getHeight(),
image.getWidth() );
445 image.getAsMatrix( im );
448 im.meanAndStdAll(m,
s);
450 for(
int k1 = 0; k1 < (int)nim.cols(); ++k1 )
451 for(
int k2 = 0; k2 < (int)nim.rows(); ++k2 )
452 nim.set_unsafe( k2, k1, (im.get_unsafe(k2,k1)-m)/
s );
472 size_t sz1 = list1.
size(), sz2 = list2.
size();
474 ASSERT_( (sz1 > 0) && (sz2 > 0) );
489 double minSAD1, minSAD2;
491 vector<int> idxLeftList, idxRightList;
494 vector<double> distCorrs(sz1);
496 int minLeftIdx = 0, minRightIdx;
500 for( lFeat = 0, itList1 = list1.
begin(); itList1 != list1.
end(); ++itList1, ++lFeat )
517 for( rFeat = 0, itList2 = list2.
begin(); itList2 != list2.
end(); ++itList2, ++rFeat )
524 d = (*itList1)->y - (*itList2)->y;
531 TPoint2D oPoint((*itList2)->x,(*itList2)->y);
534 p(0,0) = (*itList1)->x;
535 p(1,0) = (*itList1)->y;
540 epiLine.
coefs[0] = l(0,0);
541 epiLine.
coefs[1] = l(1,0);
542 epiLine.
coefs[2] = l(2,0);
549 bool c2 = options.
useXRestriction ? ((*itList1)->x - (*itList2)->x) > 0 :
true;
559 ASSERT_((*itList1)->descriptors.hasDescriptorSIFT() && (*itList2)->descriptors.hasDescriptorSIFT() );
562 distDesc = (*itList1)->descriptorSIFTDistanceTo( *(*itList2) );
565 if( distDesc < minDist1 )
572 else if ( distDesc < minDist2 )
584 ASSERT_( (*itList1)->patchSize > 0 && (*itList2)->patchSize > 0 );
596 else if(
res > maxCC2 )
605 ASSERT_((*itList1)->descriptors.hasDescriptorSURF() && (*itList2)->descriptors.hasDescriptorSURF() );
608 distDesc = (*itList1)->descriptorSURFDistanceTo( *(*itList2) );
611 if( distDesc < minDist1 )
618 else if ( distDesc < minDist2 )
627 ASSERT_((*itList1)->descriptors.hasDescriptorORB() && (*itList2)->descriptors.hasDescriptorORB() );
628 distDesc = (*itList1)->descriptorORBDistanceTo( *(*itList2) );
631 if( distDesc < minDist1 )
638 else if ( distDesc < minDist2 )
647 ASSERT_( (*itList1)->patchSize > 0 && (*itList2)->patchSize == (*itList1)->patchSize );
651 IplImage *aux1, *aux2;
652 if( (*itList1)->patch.isColor() && (*itList2)->patch.isColor() )
654 const IplImage* preAux1 = (*itList1)->patch.getAs<IplImage>();
655 const IplImage* preAux2 = (*itList2)->patch.getAs<IplImage>();
657 aux1 = cvCreateImage( cvSize( (*itList1)->patch.getHeight(), (*itList1)->patch.getWidth() ), IPL_DEPTH_8U, 1 );
658 aux2 = cvCreateImage( cvSize( (*itList2)->patch.getHeight(), (*itList2)->patch.getWidth() ), IPL_DEPTH_8U, 1 );
660 cvCvtColor( preAux1, aux1, CV_BGR2GRAY );
661 cvCvtColor( preAux2, aux2, CV_BGR2GRAY );
665 aux1 =
const_cast<IplImage*
>((*itList1)->patch.getAs<IplImage>());
666 aux2 =
const_cast<IplImage*
>((*itList2)->patch.getAs<IplImage>());
683 for(
unsigned int ii = 0; ii < (
unsigned int)aux1->height; ++ii )
684 for(
unsigned int jj = 0; jj < (
unsigned int)aux1->width; ++jj )
685 res += fabs((
double)(aux1->imageData[ii*aux1->widthStep+jj]) - ((
double)(aux2->imageData[ii*aux2->widthStep+jj])) );
686 res =
res/(255.0f*aux1->width*aux1->height);
695 else if (
res < minSAD2 )
704 bool cond1 =
false, cond2 =
false;
710 cond2 = (minDist1/minDist2) < options.
EDD_RATIO;
715 cond2 = (maxCC2/maxCC1) < options.
rCC_TH;
720 cond2 = (minDist1/minDist2) < options.
EDSD_RATIO;
725 cond2 = (minSAD1/minSAD2) < options.
SAD_RATIO;
740 int auxIdx = idxRightList[ minRightIdx ];
743 if( distCorrs[ auxIdx ] > minVal )
748 distCorrs[ minLeftIdx ] = minVal;
749 idxLeftList[ minLeftIdx ] = minRightIdx;
750 idxRightList[ minRightIdx ] = minLeftIdx;
752 distCorrs[ auxIdx ] = 1.0;
761 idxRightList[ minRightIdx ] = minLeftIdx;
762 idxLeftList[ minLeftIdx ] = minRightIdx;
763 distCorrs[ minLeftIdx ] = minVal;
773 if( !matches.empty() )
776 for(
int vCnt = 0; vCnt < (int)idxLeftList.size(); ++vCnt )
780 std::pair<CFeaturePtr, CFeaturePtr> thisMatch;
783 double dp1 = -1.0, dp2 = -1.0;
795 dp1 = sqrt( p3D.
x*p3D.
x + p3D.
y*p3D.
y + p3D.
z*p3D.
z );
796 dp2 = sqrt( (p3D.
x-
params.baseline)*(p3D.
x-
params.baseline) + p3D.
y*p3D.
y + p3D.
z*p3D.
z );
805 thisMatch.first = list1[vCnt];
806 thisMatch.second = list2[idxLeftList[vCnt]];
809 if( matches.empty() )
811 idLeft = thisMatch.first->ID;
812 idRight = thisMatch.second->ID;
816 keep_max( idLeft, thisMatch.first->ID );
819 keep_max( idRight, thisMatch.second->ID );
826 thisMatch.first->initialDepth = dp1;
827 thisMatch.first->p3D = p3D;
829 thisMatch.second->initialDepth = dp2;
834 matches.push_back( thisMatch );
838 return matches.size();
858 int hwsize = (int)(0.5*wSize);
863 for( it = mList.begin(); it != mList.end(); ++it )
865 for(
int ii = -hwsize; ii < hwsize; ++ii )
866 for(
int jj = -hwsize; jj < hwsize; ++jj )
868 idx = (int)(it->first->x) + ii;
869 idy = (int)(it->first->y) + jj;
870 if( idx >= 0 && idy >= 0 && idx < mx && idy < my )
874 for(
int ii = -hwsize; ii < hwsize; ++ii )
875 for(
int jj = -hwsize; jj < hwsize; ++jj )
877 idx = (int)(it->second->x) + ii;
878 idy = (int)(it->second->y) + jj;
879 if( idx >= 0 && idy >= 0 && idx < mx && idy < my )
894 const IplImage *im1 = patch1.
getAs<IplImage>();
895 const IplImage *im2 = patch2.
getAs<IplImage>();
897 ASSERT_( im1->width == im2->width && im1->height == im2->height );
899 for(
unsigned int ii = 0; ii < (
unsigned int)im1->height; ++ii )
900 for(
unsigned int jj = 0; jj < (
unsigned int)im1->width; ++jj )
901 res += fabs((
double)(im1->imageData[ii*im1->widthStep+jj]) - ((
double)(im2->imageData[ii*im2->widthStep+jj])) );
902 return res/(255.0f*im1->width*im1->height);
904 THROW_EXCEPTION(
"MRPT compiled without OpenCV, can't compute SAD of images!" )
919 outImg.
rectangle( (*it)->x-5, (*it)->y-5, (*it)->x+5, (*it)->y+5,
TColor(255,0,0) );
928 vector<TPoint3D> & out_points )
931 out_points.reserve( matches.size() );
934 const double disp = it->first->x - it->second->x;
939 out_points.push_back(
952 vector<TPoint3D> & vP3D,
955 vP3D.reserve( leftList.
size() );
957 for( it1 = leftList.
begin(), it2 = rightList.
begin(); it1 != leftList.
end(); ++it1, ++it2)
970 const CFeaturePtr & leftFeat,
971 const CFeaturePtr & rightFeat,
986 const double f0 = 600;
987 double nfx1 = leftFeat->x, nfy1 = leftFeat->y, nfx2 = rightFeat->x;
989 const double x = leftFeat->x * f0;
990 const double y = leftFeat->y * f0;
991 const double xd = rightFeat->x * f0;
992 const double yd = rightFeat->y * f0;
994 const double f2 = f0 * f0;
995 const double p9 = f2 *
params.F.get_unsafe(2,2);
996 const double Q00 = f2 * (
params.F.get_unsafe(0, 2) *
params.F.get_unsafe(0, 2) +
params.F.get_unsafe(1, 2) *
params.F.get_unsafe(1, 2) +
params.F.get_unsafe(2, 0) *
params.F.get_unsafe(2, 0) +
params.F.get_unsafe(2, 1) *
params.F.get_unsafe(2, 1));
998 double Jh = (std::numeric_limits<double>::max)();
1003 double xt = 0, yt = 0, xtd = 0, ytd = 0;
1005 const double p1 = (xh * xhd + xhd * xt + xh * xtd) *
params.F.get_unsafe(0, 0);
1006 const double p2 = (xh * yhd + yhd * xt + xh * ytd) *
params.F.get_unsafe(0, 1);
1007 const double p3 = (f0 * (xh + xt)) *
params.F.get_unsafe(0, 2);
1008 const double p4 = (yh * xhd + xhd * yt + yh * xtd) *
params.F.get_unsafe(1, 0);
1009 const double p5 = (yh * yhd + yhd * yt + yh * ytd) *
params.F.get_unsafe(1, 1);
1010 const double p6 = (f0 * (yh + yt)) *
params.F.get_unsafe(1, 2);
1011 const double p7 = (f0 * (xhd + xtd)) *
params.F.get_unsafe(2, 0);
1012 const double p8 = (f0 * (yhd + ytd)) *
params.F.get_unsafe(2, 1);
1014 const double udotxi = p1 + p2 + p3 + p4 + p5 + p6 + p7 + p8 + p9;
1016 const double Q11 = (xh * xh + xhd * xhd) *
params.F.get_unsafe(0, 0) *
params.F.get_unsafe(0, 0);
1017 const double Q22 = (xh * xh + yhd * yhd) *
params.F.get_unsafe(0, 1) *
params.F.get_unsafe(0, 1);
1018 const double Q44 = (yh * yh + xhd * xhd) *
params.F.get_unsafe(1, 0) *
params.F.get_unsafe(1, 0);
1019 const double Q55 = (yh * yh + yhd * yhd) *
params.F.get_unsafe(1, 1) *
params.F.get_unsafe(1, 1);
1020 const double Q12 = xhd * yhd *
params.F.get_unsafe(0, 0) *
params.F.get_unsafe(0, 1);
1021 const double Q13 = f0 * xhd *
params.F.get_unsafe(0, 0) *
params.F.get_unsafe(0, 2);
1022 const double Q14 = xh * yh *
params.F.get_unsafe(0, 0) *
params.F.get_unsafe(1, 0);
1023 const double Q17 = f0 * xh *
params.F.get_unsafe(0, 0) *
params.F.get_unsafe(2, 0);
1024 const double Q23 = f0 * yhd *
params.F.get_unsafe(0, 1) *
params.F.get_unsafe(0, 2);
1025 const double Q25 = xh * yh *
params.F.get_unsafe(0, 1) *
params.F.get_unsafe(1, 1);
1026 const double Q28 = f0 * xh *
params.F.get_unsafe(0, 1) *
params.F.get_unsafe(2, 1);
1027 const double Q45 = xhd * yhd *
params.F.get_unsafe(1, 0) *
params.F.get_unsafe(1, 1);
1028 const double Q46 = f0 * xhd *
params.F.get_unsafe(1, 0) *
params.F.get_unsafe(1, 2);
1029 const double Q47 = f0 * yh *
params.F.get_unsafe(1, 0) *
params.F.get_unsafe(2, 0);
1030 const double Q56 = f0 * yhd *
params.F.get_unsafe(1, 1) *
params.F.get_unsafe(1, 2);
1031 const double Q58 = f0 * yh *
params.F.get_unsafe(1, 1) *
params.F.get_unsafe(2, 1);
1033 const double udotV0xiu = Q00 + Q11 + Q22 + Q44 + Q55
1034 + 2.0 * (Q12 + Q13 + Q14 + Q17 + Q23 + Q25 + Q28 + Q45 + Q46 + Q47 + Q56 + Q58);
1036 ASSERT_( fabs(udotV0xiu) > 1e-5 );
1038 const double C = udotxi / udotV0xiu;
1040 xt = C * (
params.F.get_unsafe(0, 0) * xhd +
params.F.get_unsafe(0, 1) * yhd + f0 *
params.F.get_unsafe(0, 2));
1041 yt = C * (
params.F.get_unsafe(1, 0) * xhd +
params.F.get_unsafe(1, 1) * yhd + f0 *
params.F.get_unsafe(1, 2));
1042 xtd = C * (
params.F.get_unsafe(0, 0) * xh +
params.F.get_unsafe(1, 0) * yh + f0 *
params.F.get_unsafe(2, 0));
1043 ytd = C * (
params.F.get_unsafe(0, 1) * xh +
params.F.get_unsafe(1, 1) * yh + f0 *
params.F.get_unsafe(2, 1));
1045 const double Jt = xt * xt + yt * yt + xtd * xtd + ytd * ytd;
1047 if ((std::abs)(Jt - Jh) <= 1e-5) {
1064 double disp = nfx1 - nfx2;
1065 double aux =
params.baseline/disp;
1066 p3D.
x = (nfx1-
params.K(0,2))*aux;
1067 p3D.
y = (nfy1-
params.K(1,2))*aux;
1088 for(itList = mfList.begin(); itList != mfList.end();)
1090 float disp = ( itList->first->x - itList->second->x );
1092 itList = mfList.erase( itList );
1097 float x3D = ( itList->first->x -
param.K(0,2) ) * ( (
param.baseline) ) / disp;
1098 float y3D = ( itList->first->y -
param.K(1,2) ) * ( (
param.baseline) ) / disp;
1099 float z3D = (
param.K(0,0) ) * ( (
param.baseline) ) / disp;
1102 if ( (z3D <
param.minZ) || (z3D >
param.maxZ) )
1103 itList = mfList.erase( itList );
1112 norm3D *= -1/norm3D.
norm();
1116 lm.
ID = itList->first->ID;
1124 switch(
param.uncPropagation )
1130 float c0 =
param.K(0,2);
1131 float r0 =
param.K(1,2);
1133 float disp2 =
square( itList->first->x - itList->second->x );
1136 lm.
pose_cov_12 = stdDisp2*base2*( itList->first->x - c0 )*( itList->first->y - r0 )/
square(disp2);
1137 lm.
pose_cov_13 = stdDisp2*base2*sqrt(foc2)*( itList->first->x - c0 )/
square(disp2);
1139 lm.
pose_cov_23 = stdDisp2*base2*sqrt(foc2)*( itList->first->y - r0 )/
square(disp2);
1147 unsigned int Na = 3;
1150 float k =
param.factor_k;
1152 float w0 = k/(Na + k);
1153 float w1 = 1/(2*(Na + k));
1159 Pa(0,0) = Pa(1,1) = ( Na + k ) *
square(
param.stdPixel );
1169 B.resize( 2*Na + 1 );
1180 meanA[0] = itList->first->x;
1181 meanA[1] = itList->first->y;
1185 meanB.
x = w0*x3D; meanB.
y = w0*y3D; meanB.
z = w0*z3D;
1186 B[0].x = x3D; B[0].y = y3D; B[0].z = z3D;
1188 for( i = 1; i <= 2*Na; i++ )
1193 L.extractRowAsCol( i-1, vAux );
1194 myPoint[0] = meanA[0] + vAux[0];
1195 myPoint[1] = meanA[1] + vAux[1];
1196 myPoint[2] = meanA[2] + vAux[2];
1200 L.extractRowAsCol( (i-Na)-1, vAux );
1201 myPoint[0] = meanA[0] - vAux[0];
1202 myPoint[1] = meanA[1] - vAux[1];
1203 myPoint[2] = meanA[2] - vAux[2];
1207 x3D = ( myPoint[0] -
param.K(0,2) ) * ( (
param.baseline) ) / myPoint[2];
1208 y3D = ( myPoint[1] -
param.K(1,2) ) * ( (
param.baseline) ) / myPoint[2];
1209 z3D = (
param.K(0,0) ) * ( (
param.baseline) ) / myPoint[2];
1212 meanB.
x = meanB.
x +
w1*x3D;
1213 meanB.
y = meanB.
y +
w1*y3D;
1214 meanB.
z = meanB.
z +
w1*z3D;
1223 for( i = 0; i <= 2*Na; i++ )
1231 v(0,0) = B[i].x - meanB.
x;
1232 v(1,0) = B[i].y - meanB.
y;
1233 v(2,0) = B[i].z - meanB.
z;
1235 Pb = Pb + weight*(
v*
v.transpose());
1251 unsigned int Na = 3;
1254 float a =
param.factor_a;
1255 float b =
param.factor_b;
1256 float k =
param.factor_k;
1258 float lambda =
square(
a)*(Na + k) - Na;
1260 float w0_m = lambda/(Na + lambda);
1261 float w0_c = w0_m + (1 -
square(
a) +
b);
1262 float w1 = 1/(2*(Na + lambda));
1268 Pa(0,0) = Pa(1,1) = ( Na + lambda ) *
square(
param.stdPixel );
1269 Pa(2,2) = ( Na + lambda ) *
square(
param.stdDisp );
1278 B.resize( 2*Na + 1 );
1289 meanA[0] = itList->first->x;
1290 meanA[1] = itList->first->y;
1294 meanB.
x = w0_m*x3D; meanB.
y = w0_m*y3D; meanB.
z = w0_m*z3D;
1295 B[0].x = x3D; B[0].y = y3D; B[0].z = z3D;
1297 for( i = 1; i <= 2*Na; i++ )
1302 L.extractRowAsCol( i-1, vAux );
1303 myPoint = meanA + vAux;
1310 L.extractRowAsCol( (i-Na)-1, vAux );
1311 myPoint = meanA - vAux;
1318 x3D = ( myPoint[0] -
param.K(0,2) ) * ( (
param.baseline) ) / myPoint[2];
1319 y3D = ( myPoint[1] -
param.K(1,2) ) * ( (
param.baseline) ) / myPoint[2];
1320 z3D = (
param.K(0,0) ) * ( (
param.baseline) ) / myPoint[2];
1323 meanB.
x = meanB.
x +
w1*x3D;
1324 meanB.
y = meanB.
y +
w1*y3D;
1325 meanB.
z = meanB.
z +
w1*z3D;
1334 for( i = 0; i <= 2*Na; i++ )
1342 v(0,0) = B[i].x - meanB.
x;
1343 v(1,0) = B[i].y - meanB.
y;
1344 v(2,0) = B[i].z - meanB.
z;
1346 Pb = Pb + weight*(
v*
v.transpose());
1388 for(itListL = leftList.
begin(), itListR = rightList.
begin(); itListL != leftList.
end();)
1390 float disp = ( (*itListL)->x - (*itListR)->x );
1393 itListL = leftList.
erase( itListL );
1394 itListR = rightList.
erase( itListR );
1399 float x3D = ( (*itListL)->x -
param.K(0,2) ) * ( (
param.baseline) ) / disp;
1400 float y3D = ( (*itListL)->y -
param.K(1,2) ) * ( (
param.baseline) ) / disp;
1401 float z3D = (
param.K(0,0) ) * ( (
param.baseline) ) / disp;
1404 if ( (z3D <
param.minZ) || (z3D >
param.maxZ) )
1406 itListL = leftList.
erase( itListL );
1407 itListR = rightList.
erase( itListR );
1417 norm3D *= -1/norm3D.
norm();
1421 lm.
ID = (*itListL)->ID;
1430 switch(
param.uncPropagation )
1436 float c0 =
param.K(0,2);
1437 float r0 =
param.K(1,2);
1439 float disp2 =
square( (*itListL)->x - (*itListR)->x );
1442 lm.
pose_cov_12 = stdDisp2*base2*( (*itListL)->x - c0 )*( (*itListL)->y - r0 )/
square(disp2);
1443 lm.
pose_cov_13 = stdDisp2*base2*sqrt(foc2)*( (*itListL)->x - c0 )/
square(disp2);
1445 lm.
pose_cov_23 = stdDisp2*base2*sqrt(foc2)*( (*itListL)->y - r0 )/
square(disp2);
1453 unsigned int Na = 3;
1456 float k =
param.factor_k;
1458 float w0 = k/(Na + k);
1459 float w1 = 1/(2*(Na + k));
1465 Pa(0,0) = Pa(1,1) = ( Na + k ) *
square(
param.stdPixel );
1475 B.resize( 2*Na + 1 );
1486 meanA[0] = (*itListL)->x;
1487 meanA[1] = (*itListL)->y;
1491 meanB.
x = w0*x3D; meanB.
y = w0*y3D; meanB.
z = w0*z3D;
1492 B[0].x = x3D; B[0].y = y3D; B[0].z = z3D;
1494 for( i = 1; i <= 2*Na; i++ )
1499 L.extractRowAsCol( i-1, vAux );
1500 myPoint[0] = meanA[0] + vAux[0];
1501 myPoint[1] = meanA[1] + vAux[1];
1502 myPoint[2] = meanA[2] + vAux[2];
1506 L.extractRowAsCol( (i-Na)-1, vAux );
1507 myPoint[0] = meanA[0] - vAux[0];
1508 myPoint[1] = meanA[1] - vAux[1];
1509 myPoint[2] = meanA[2] - vAux[2];
1513 x3D = ( myPoint[0] -
param.K(0,2) ) * ( (
param.baseline) ) / myPoint[2];
1514 y3D = ( myPoint[1] -
param.K(1,2) ) * ( (
param.baseline) ) / myPoint[2];
1515 z3D = (
param.K(0,0) ) * ( (
param.baseline) ) / myPoint[2];
1518 meanB.
x = meanB.
x +
w1*x3D;
1519 meanB.
y = meanB.
y +
w1*y3D;
1520 meanB.
z = meanB.
z +
w1*z3D;
1529 for( i = 0; i <= 2*Na; i++ )
1537 v(0,0) = B[i].x - meanB.
x;
1538 v(1,0) = B[i].y - meanB.
y;
1539 v(2,0) = B[i].z - meanB.
z;
1541 Pb = Pb + weight*(
v*
v.transpose());
1557 unsigned int Na = 3;
1560 float a =
param.factor_a;
1561 float b =
param.factor_b;
1562 float k =
param.factor_k;
1564 float lambda =
square(
a)*(Na + k) - Na;
1566 float w0_m = lambda/(Na + lambda);
1567 float w0_c = w0_m + (1 -
square(
a) +
b);
1568 float w1 = 1/(2*(Na + lambda));
1574 Pa(0,0) = Pa(1,1) = ( Na + lambda ) *
square(
param.stdPixel );
1575 Pa(2,2) = ( Na + lambda ) *
square(
param.stdDisp );
1584 B.resize( 2*Na + 1 );
1595 meanA[0] = (*itListL)->x;
1596 meanA[1] = (*itListL)->y;
1600 meanB.
x = w0_m*x3D; meanB.
y = w0_m*y3D; meanB.
z = w0_m*z3D;
1601 B[0].x = x3D; B[0].y = y3D; B[0].z = z3D;
1603 for( i = 1; i <= 2*Na; i++ )
1608 L.extractRowAsCol( i-1, vAux );
1609 myPoint = meanA + vAux;
1616 L.extractRowAsCol( (i-Na)-1, vAux );
1617 myPoint = meanA - vAux;
1624 x3D = ( myPoint[0] -
param.K(0,2) ) * ( (
param.baseline) ) / myPoint[2];
1625 y3D = ( myPoint[1] -
param.K(1,2) ) * ( (
param.baseline) ) / myPoint[2];
1626 z3D = (
param.K(0,0) ) * ( (
param.baseline) ) / myPoint[2];
1629 meanB.
x = meanB.
x +
w1*x3D;
1630 meanB.
y = meanB.
y +
w1*y3D;
1631 meanB.
z = meanB.
z +
w1*z3D;
1640 for( i = 0; i <= 2*Na; i++ )
1648 v(0,0) = B[i].x - meanB.
x;
1649 v(1,0) = B[i].y - meanB.
y;
1650 v(2,0) = B[i].z - meanB.
z;
1652 Pb = Pb + weight*(
v*
v.transpose());
1682 const double & baseline,
1684 const vector<double> & sg,
1689 double f = intrinsicParams(0,0);
1690 double x0 = intrinsicParams(0,2);
1691 double y0 = intrinsicParams(1,2);
1692 double b = baseline;
1693 double sg_c2 =
square( sg[0] );
1694 double sg_r2 =
square( sg[1] );
1695 double sg_d2 =
square( sg[2] );
1698 itMatchList != inMatches.end();
1701 double x = itMatchList->first->x;
1702 double y = itMatchList->first->y;
1704 double d = itMatchList->first->x - itMatchList->second->x;
1710 double X = (
x - x0 ) *
b / d;
1711 double Y = (
y - y0 ) *
b / d;
1712 double Z = f *
b / d;
1722 m.
yaw = atan2( Y,X );
1735 aux.get_unsafe( 0, 0 ) = k*(sg_c2 + sg_d2*
square(
x-x0)/d2);
1736 aux.get_unsafe( 0, 1 ) = aux.get_unsafe( 1, 0 ) = k*(sg_d2*(
x-x0)*(
y-y0)/d2);
1737 aux.get_unsafe( 0, 2 ) = aux.get_unsafe( 2, 0 ) = k*(sg_d2*(
x-x0)*f/d2);
1739 aux.get_unsafe( 1, 1 ) = k*(sg_r2 + sg_d2*
square(
y-y0)/d2);
1740 aux.get_unsafe( 1, 2 ) = aux.get_unsafe( 2, 1 ) = k*(sg_d2*(
y-y0)*f/d2);
1742 aux.get_unsafe( 2, 2 ) = k*(sg_d2*
square(f)/d2);
1763 JG.set_unsafe( 0, 0, X/m.
range );
1764 JG.set_unsafe( 0, 1, Y/m.
range );
1765 JG.set_unsafe( 0, 2, Z/m.
range );
1769 JG.set_unsafe( 1, 2, 0 );
1801 const vector<double> & sg,
1808 unsigned int id = 0;
1828 double sg_c2 =
square( sg[0] );
1829 double sg_r2 =
square( sg[1] );
1830 double sg_d2 =
square( sg[2] );
1833 itMatchList != matchList.end();
1834 itMatchList++,
id++ )
1836 double x = itMatchList->first->x;
1837 double y = itMatchList->first->y;
1839 double d = itMatchList->first->x - itMatchList->second->x;
1845 double X = (
x - x0 ) *
b / d;
1846 double Y = (
y - y0 ) *
b / d;
1847 double Z = f *
b / d;
1859 m.
yaw = atan2( X,Z );
1860 m.
pitch = atan2( Y,Z );
1871 aux.get_unsafe( 0, 0 ) = k*(sg_c2 + sg_d2*
square(
x-x0)/d2);
1872 aux.get_unsafe( 0, 1 ) = aux.get_unsafe( 1, 0 ) = k*(sg_d2*(
x-x0)*(
y-y0)/d2);
1873 aux.get_unsafe( 0, 2 ) = aux.get_unsafe( 2, 0 ) = k*(sg_d2*(
x-x0)*f/d2);
1875 aux.get_unsafe( 1, 1 ) = k*(sg_r2 + sg_d2*
square(
y-y0)/d2);
1876 aux.get_unsafe( 1, 2 ) = aux.get_unsafe( 2, 1 ) = k*(sg_d2*(
y-y0)*f/d2);
1878 aux.get_unsafe( 2, 2 ) = k*(sg_d2*
square(f)/d2);
1899 JG.set_unsafe( 0, 0, X/m.
range );
1900 JG.set_unsafe( 0, 1, Y/m.
range );
1901 JG.set_unsafe( 0, 2, Z/m.
range );
1905 JG.set_unsafe( 1, 2, 0 );
1952 m.
yaw = atan2( itCloud->pose_mean.y, itCloud->pose_mean.x );
1953 m.
pitch = -sin( itCloud->pose_mean.z/m.
range );
1974 #if MRPT_HAS_OPENCV && MRPT_OPENCV_VERSION_NUM>=0x211 1976 cv::Mat *mapx1, *mapy1, *mapx2, *mapy2;
1977 mapx1 =
static_cast<cv::Mat*
>(outMap1x);
1978 mapy1 =
static_cast<cv::Mat*
>(outMap1y);
1979 mapx2 =
static_cast<cv::Mat*
>(outMap2x);
1980 mapy2 =
static_cast<cv::Mat*
>(outMap2y);
1982 const int resX = cam1.
ncols;
1983 const int resY = cam1.
nrows;
1989 rcTrans[0] = hMatrix(0,3);
1990 rcTrans[1] = hMatrix(1,3);
1991 rcTrans[2] = hMatrix(2,3);
1994 for(
unsigned int i = 0; i < 3; ++i)
1995 for(
unsigned int j = 0; j < 3; ++j)
1996 m1[i][j] = hMatrix(i,j);
1998 double ipl[3][3], ipr[3][3], dpl[5], dpr[5];
1999 for(
unsigned int i = 0; i < 3; ++i )
2000 for(
unsigned int j = 0; j < 3; ++j )
2006 for(
unsigned int i = 0; i < 5; ++i )
2008 dpl[i] = cam1.
dist[i];
2009 dpr[i] = cam2.
dist[i];
2012 cv::Mat
R( 3, 3, CV_64F, &m1 );
2013 cv::Mat T( 3, 1, CV_64F, &rcTrans );
2015 cv::Mat K1(3,3,CV_64F,ipl);
2016 cv::Mat K2(3,3,CV_64F,ipr);
2017 cv::Mat D1(1,5,CV_64F,dpl);
2018 cv::Mat D2(1,5,CV_64F,dpr);
2020 double _R1[3][3], _R2[3][3], _P1[3][4], _P2[3][4], _Q[4][4];
2021 cv::Mat R1(3,3,CV_64F,_R1);
2022 cv::Mat R2(3,3,CV_64F,_R2);
2023 cv::Mat P1(3,4,CV_64F,_P1);
2024 cv::Mat P2(3,4,CV_64F,_P2);
2025 cv::Mat Q(4,4,CV_64F,_Q);
2027 cv::Size nSize(resX,resY);
2030 #if MRPT_OPENCV_VERSION_NUM<0x210 2038 cv::CALIB_ZERO_DISPARITY
2040 #elif MRPT_OPENCV_VERSION_NUM<0x230 2051 cv::CALIB_ZERO_DISPARITY
2061 cv::CALIB_ZERO_DISPARITY,
2068 cv::initUndistortRectifyMap( K1, D1, R1, P1, cv::Size(resX,resY), CV_32FC1, *mapx1, *mapy1 );
2069 cv::initUndistortRectifyMap( K2, D2, R2, P2, cv::Size(resX,resY), CV_32FC1, *mapx2, *mapy2 );
2072 THROW_EXCEPTION(
"The MRPT has been compiled with MRPT_HAS_OPENCV = 0 or OpenCV version is < 2.1.1!");
2082 vision::TROI::TROI(
float x1,
float x2,
float y1,
float y2,
float z1,
float z2) : xMin(x1), xMax(x2), yMin(y1), yMax(y2), zMin(z1), zMax(z2)
2102 uncPropagation( Prop_Linear ),
2103 baseline ( 0.119f ),
2115 F.set_unsafe(1,2,-1);
2116 F.set_unsafe(2,1,1);
2124 const string & section)
2143 for (
unsigned int ii = 0; ii < 3; ++ii )
2144 for (
unsigned int jj = 0; jj < 3; ++jj)
2145 K(ii,jj) = k_vec[ii*3+jj];
2149 for (
unsigned int ii = 0; ii < 3; ++ii )
2150 for (
unsigned int jj = 0; jj < 3; ++jj)
2151 F(ii,jj) = f_vec[ii*3+jj];
2170 out.
printf(
"\n----------- [vision::TStereoSystemParams] ------------ \n");
2171 out.
printf(
"Method for 3D Uncert. \t= ");
2175 out.
printf(
"Linear propagation\n");
2178 out.
printf(
"Unscented Transform\n");
2181 out.
printf(
"Scaled Unscented Transform\n");
2185 out.
printf(
"K\t\t\t= [%f\t%f\t%f]\n",
K(0,0),
K(0,1),
K(0,2));
2186 out.
printf(
" \t\t\t [%f\t%f\t%f]\n",
K(1,0),
K(1,1),
K(1,2));
2187 out.
printf(
" \t\t\t [%f\t%f\t%f]\n",
K(2,0),
K(2,1),
K(2,2));
2189 out.
printf(
"F\t\t\t= [%f\t%f\t%f]\n",
F(0,0),
F(0,1),
F(0,2));
2190 out.
printf(
" \t\t\t [%f\t%f\t%f]\n",
F(1,0),
F(1,1),
F(1,2));
2191 out.
printf(
" \t\t\t [%f\t%f\t%f]\n",
F(2,0),
F(2,1),
F(2,2));
2203 out.
printf(
"-------------------------------------------------------- \n");
2211 useEpipolarRestriction ( true ),
2212 hasFundamentalMatrix ( false ),
2213 parallelOpticalAxis ( true ),
2214 useXRestriction ( true ),
2215 addMatches( false ),
2216 useDisparityLimits( false ),
2218 min_disp(1.0f), max_disp(1e4f),
2220 matching_method ( mmCorrelation ),
2221 epipolar_TH ( 1.5f ),
2224 maxEDD_TH ( 90.0f ),
2229 minDCC_TH ( 0.025f ),
2233 maxEDSD_TH ( 0.15f ),
2234 EDSD_RATIO ( 0.6f ),
2241 estimateDepth ( false ),
2242 maxDepthThreshold ( 15.0 )
2251 const string & section )
2309 out.
printf(
"\n----------- [vision::TMatchingOptions] ------------ \n");
2310 out.
printf(
"Matching method: ");
2314 out.
printf(
"Cross Correlation\n");
2317 out.
printf(
"Ā· Max. Ratio CC Threshold: %f\n",
rCC_TH);
2320 out.
printf(
"SIFT descriptor\n");
2325 out.
printf(
"SURF descriptor\n");
2340 out.
printf(
"Using epipolar restriction?: ");
2342 out.
printf(
"Has Fundamental Matrix?: ");
2344 out.
printf(
"Are camera axis parallel?: ");
2346 out.
printf(
"Use X-coord restriction?: ");
2348 out.
printf(
"Use disparity limits?: ");
2352 out.
printf(
"Estimate depth?: ");
2362 out.
printf(
"Add matches to list?: ");
2364 out.
printf(
"-------------------------------------------------------- \n");
void clear()
Erase all the contents of the map.
void VISION_IMPEXP projectMatchedFeatures(const CMatchedFeatureList &matches, const mrpt::utils::TStereoCamera &stereo_camera, std::vector< mrpt::math::TPoint3D > &out_points)
float fieldOfView_yaw
Information about the sensor: Ranges, in meters (0: there is no limits)
A pair (x,y) of pixel coordinates (subpixel resolution).
float EDD_RATIO
Boundary Ratio between the two lowest EDD.
double x() const
Common members of all points & poses classes.
TMatchingOptions()
Constructor.
GLclampf GLclampf GLclampf alpha
float rCC_TH
Maximum Ratio Between the two highest CC values.
mrpt::math::CMatrixDouble33 F
Stereo Fundamental matrix.
bool read_bool(const std::string §ion, const std::string &name, bool defaultValue, bool failIfNotFound=false) const
double VISION_IMPEXP computeSAD(const mrpt::utils::CImage &patch1, const mrpt::utils::CImage &patch2)
Calculates the Sum of Absolutes Differences (range [0,1]) between two patches.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
double maxORB_dist
Maximun distance between ORB descriptors.
Declares a matrix of booleans (non serializable).
mrpt::utils::CImage imageLeft
Image from the left camera (this image will be ALWAYS present)
float range
The sensed landmark distance, in meters.
bool estimateDepth
Whether or not estimate the 3D position of the real features for the matches (only with parallelOptic...
This namespace provides a OS-independent interface to many useful functions: filenames manipulation...
float read_float(const std::string §ion, const std::string &name, float defaultValue, bool failIfNotFound=false) const
bool useXRestriction
Whether or not employ the x-coord restriction for finding correspondences (bumblebee camera...
void VISION_IMPEXP cloudsToMatchedList(const mrpt::obs::CObservationVisualLandmarks &cloud1, const mrpt::obs::CObservationVisualLandmarks &cloud2, mrpt::utils::TMatchingPairList &outList)
Transform two clouds of 3D points into a matched list of points ...
A class for storing images as grayscale or RGB bitmaps.
Linear propagation of the uncertainty.
void setRightMaxID(const TFeatureID &rightID)
double SAD_RATIO
Boundary Ratio between the two highest SAD.
#define THROW_EXCEPTION(msg)
void resize(unsigned int width, unsigned int height, TImageChannels nChannels, bool originTopLeft)
Changes the size of the image, erasing previous contents (does NOT scale its current content...
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
void VISION_IMPEXP StereoObs2BRObs(const mrpt::obs::CObservationStereoImages &inObs, const std::vector< double > &sg, mrpt::obs::CObservationBearingRange &outObs)
Converts a stereo images observation into a bearing and range observation.
double cy() const
Get the value of the principal point y-coordinate (in pixels).
Declares a class derived from "CObservation" that stores a Landmarks Map as seen from a stereo camera...
double norm() const
Point norm.
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
GLenum GLsizei GLenum GLenum const GLvoid * image
TInternalFeatList::const_iterator const_iterator
void rectangle(int x0, int y0, int x1, int y1, const mrpt::utils::TColor color, unsigned int width=1)
Draws a rectangle (an empty rectangle, without filling)
float epipolar_TH
Epipolar constraint (rows of pixels)
const Scalar * const_iterator
float minZ
Maximum allowed distance.
float EDSD_RATIO
Boundary Ratio between the two lowest SURF EDSD.
void VISION_IMPEXP addFeaturesToImage(const mrpt::utils::CImage &inImg, const CFeatureList &theList, mrpt::utils::CImage &outImg)
Draw rectangles around each of the features on a copy of the input image.
double z
X,Y,Z coordinates.
bool useEpipolarRestriction
Whether or not take into account the epipolar restriction for finding correspondences.
void VISION_IMPEXP projectMatchedFeature(const CFeaturePtr &leftFeat, const CFeaturePtr &rightFeat, mrpt::math::TPoint3D &p3D, const TStereoSystemParams ¶ms=TStereoSystemParams())
Computes the 3D position of a particular matched feature.
Matching by Hamming distance between ORB descriptors.
const T * getAs() const
Returns a pointer to a const T* containing the image - the idea is to call like "img.getAs<IplImage>()" so we can avoid here including OpenCV's headers.
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion) MRPT_OVERRIDE
This method load the options from a ".ini"-like file or memory-stored string list.
float factor_k
K factor for the UT.
Structure to hold the parameters of a pinhole stereo camera model.
This class allows loading and storing values and vectors of different types from a configuration text...
T square(const T x)
Inline function for the square of a number.
bool useDisparityLimits
Whether or not use limits (min,max) for the disparity, see also 'min_disp, max_disp'.
float stdPixel
Standard deviation of the error in feature detection.
std::vector< mrpt::vision::CFeaturePtr > features
The set of features from which the landmark comes.
float yaw
The sensed landmark direction, in radians, measured as the yaw (azimuth) and pitch (negative elevatio...
mrpt::math::TPoint3D VISION_IMPEXP pixelTo3D(const mrpt::utils::TPixelCoordf &xy, const mrpt::math::CMatrixDouble33 &A)
Extract a UNITARY 3D vector in the direction of a 3D point, given from its (x,y) pixels coordinates...
double fx() const
Get the value of the focal length x-value (in pixels).
int read_int(const std::string §ion, const std::string &name, int defaultValue, bool failIfNotFound=false) const
mrpt::poses::CPose3DQuat cameraPose
The pose of the LEFT camera, relative to the robot.
int32_t landmarkID
The ID of the sensed beacon, or INVALID_LANDMARK_ID (-1) if the sensor does not identify the landmark...
Matching by Euclidean distance between SIFT descriptors.
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
bool parallelOpticalAxis
Whether or not the stereo rig has the optical axes parallel.
float minDCC_TH
Minimum Difference Between the Maximum Cross Correlation Values.
This base provides a set of functions for maths stuff.
A class for storing a map of 3D probabilistic landmarks.
TUnc_Prop_Method uncPropagation
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
void getMaxID(const TListIdx &idx, TFeatureID &firstListID, TFeatureID &secondListID)
Returns the maximum ID of the features in the list.
Parameters associated to a stereo system.
bool addMatches
Whether or not to add the matches found into the input matched list (if false the input list will be ...
void push_back(const CLandmark &lm)
The object is copied, thus the original copy passed as a parameter can be released.
Matching by Euclidean distance between SURF descriptors.
void VISION_IMPEXP openCV_cross_correlation(const mrpt::utils::CImage &img, const mrpt::utils::CImage &patch_img, size_t &x_max, size_t &y_max, double &max_val, int x_search_ini=-1, int y_search_ini=-1, int x_search_size=-1, int y_search_size=-1)
Computes the correlation between this image and another one, encapsulating the openCV function cvMatc...
void read_vector(const std::string §ion, const std::string &name, const VECTOR_TYPE &defaultValue, VECTOR_TYPE &outValues, bool failIfNotFound=false) const
Reads a configuration parameter of type vector, stored in the file as a string: "[v1 v2 v3 ...
float max_disp
Disparity limits, see also 'useDisparityLimits'.
float maxY
Maximum allowed height.
CImage grayscale() const
Returns a grayscale version of the image, or itself if it is already a grayscale image.
Observation class for either a pair of left+right or left+disparity images from a stereo camera...
float fieldOfView_pitch
Information about the sensor: The "field-of-view" of the sensor, in radians (for pitch )...
This namespace contains representation of robot actions and observations.
double coefs[3]
Line coefficients, stored as an array: .
Classes for computer vision, detectors, features, etc.
double VISION_IMPEXP computeMsd(const mrpt::utils::TMatchingPairList &list, const poses::CPose3D &Rt)
Computes the mean squared distance between a set of 3D correspondences ...
Uncertainty propagation through the Unscented Transformation.
double maxDepthThreshold
The maximum allowed depth for the matching. If its computed depth is larger than this, the match won't be considered.
iterator erase(const iterator &it)
uint64_t TFeatureID
Definition of a feature ID.
void setFromIplImageReadOnly(void *iplImage)
Reads the image from a OpenCV IplImage object (WITHOUT making a copy) and from now on the image canno...
void VISION_IMPEXP flip(mrpt::utils::CImage &img)
Invert an image using OpenCV function.
void set_unsafe(size_t row, size_t col, const T &v)
Fast but unsafe method to write a value in the matrix.
double cx() const
Get the value of the principal point x-coordinate (in pixels).
mrpt::utils::TCamera leftCamera
Parameters for the left/right cameras: individual intrinsic and distortion parameters of the cameras...
A list of visual features, to be used as output by detectors, as input/output by trackers, etc.
void keep_max(T &var, const K test_val)
If the second argument is above the first one, set the first argument to this higher value...
void VISION_IMPEXP rowChecking(CFeatureList &leftList, CFeatureList &rightList, float threshold=1.0)
Search for correspondences which are not in the same row and deletes them.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
float VISION_IMPEXP computeMainOrientation(const mrpt::utils::CImage &image, unsigned int x, unsigned int y)
Computes the main orientation of a set of points with an image (for using in SIFT-based algorithms) ...
void setSensorPose(const mrpt::poses::CPose3D &newSensorPose) MRPT_OVERRIDE
A general method to change the sensor pose on the robot.
mrpt::utils::CImage imageRight
Image from the right camera, only contains a valid image if hasImageRight == true.
Each one of the measurements:
mrpt::math::CMatrixDouble33 intrinsicParams
Matrix of intrinsic parameters (containing the focal length and principal point coordinates) ...
TStereoSystemParams()
Initilization of default parameters.
Matching by sum of absolute differences of the image patches.
double maxSAD_TH
Minimum Euclidean Distance Between Sum of Absolute Differences.
void setFromMatrix(const Eigen::MatrixBase< Derived > &m, bool matrix_is_normalized=true)
Set the image from a matrix, interpreted as grayscale intensity values, in the range [0...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
The class for storing "landmarks" (visual or laser-scan-extracted features,...)
void dumpToTextStream(mrpt::utils::CStream &out) const MRPT_OVERRIDE
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
void setFromImageReadOnly(const CImage &other_img)
Sets the internal IplImage pointer to that of another given image, WITHOUT making a copy...
mrpt::math::CArrayDouble< 5 > dist
[k1 k2 t1 t2 k3] -> k_i: parameters of radial distortion, t_i: parameters of tangential distortion (d...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
mrpt::math::TPoint3D normal
The "normal" to the landmark, i.e. a unitary 3D vector towards the viewing direction, or a null vector if not applicable.
float maxZ
Maximum allowed distance.
mrpt::poses::CPose3DQuat rightCameraPose
The pose of the right camera, relative to the left one: Note that using the conventional reference co...
void VISION_IMPEXP computeStereoRectificationMaps(const mrpt::utils::TCamera &cam1, const mrpt::utils::TCamera &cam2, const mrpt::poses::CPose3D &rightCameraPose, void *outMap1x, void *outMap1y, void *outMap2x, void *outMap2y)
Computes a pair of x-and-y maps for stereo rectification from a pair of cameras and the relative pose...
size_t VISION_IMPEXP matchFeatures(const CFeatureList &list1, const CFeatureList &list2, CMatchedFeatureList &matches, const TMatchingOptions &options=TMatchingOptions(), const TStereoSystemParams ¶ms=TStereoSystemParams())
Find the matches between two lists of features which must be of the same type.
This observation represents a number of range-bearing value pairs, each one for a detected landmark...
A structure containing options for the matching.
void extract_patch(CImage &patch, const unsigned int col=0, const unsigned int row=0, const unsigned int width=1, const unsigned int height=1) const
Extract a patch from this image, saveing it into "patch" (its previous contents will be overwritten)...
uint32_t nrows
Camera resolution.
Matching by cross correlation of the image patches.
void setLeftMaxID(const TFeatureID &leftID)
Explicitly set the max IDs values to certain values.
void VISION_IMPEXP generateMask(const CMatchedFeatureList &mList, mrpt::math::CMatrixBool &mask1, mrpt::math::CMatrixBool &mask2, int wSize=10)
Calculates the Sum of Absolutes Differences (range [0,1]) between two patches.
bool hasFundamentalMatrix
Whether or not there is a fundamental matrix.
mrpt::maps::CLandmarksMap landmarks
The landmarks, with coordinates origin in the camera reference system.
size_t getColCount() const
Number of columns in the matrix.
A matrix of dynamic size.
size_t getRowCount() const
Number of rows in the matrix.
int round(const T value)
Returns the closer integer (int) to x.
TInternalFeatList::iterator iterator
float maxEDSD_TH
Maximum Euclidean Distance Between SURF Descriptors.
float minCC_TH
Minimum Value of the Cross Correlation.
float factor_a
Alpha factor for SUT.
internal::TSequenceLandmarks::const_iterator const_iterator
float factor_b
Beta factor for the SUT.
float maxEDD_TH
Maximum Euclidean Distance Between SIFT Descriptors.
bool isColor() const
Returns true if the image is RGB, false if it is grayscale.
dynamic_vector< double > CVectorDouble
Column vector, like Eigen::MatrixXd, but automatically initialized to zeros since construction...
void dumpToTextStream(mrpt::utils::CStream &out) const MRPT_OVERRIDE
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
void VISION_IMPEXP deleteRepeatedFeats(CFeatureList &list)
Explore the feature list and removes features which are in the same coordinates.
bool validCovariances
True: The individual 3x3 covariance matrices must be taken into account, false (default): All the mea...
void VISION_IMPEXP getDispersion(const CFeatureList &list, mrpt::math::CVectorFloat &std, mrpt::math::CVectorFloat &mean)
Computes the dispersion of the features in the image.
TFeatureType get_type() const
The type of the first feature in the list.
mrpt::math::TPoint3D pose_mean
The mean of the landmark 3D position.
double distance(const TPoint2D &point) const
Distance from a given point.
This class is a "CSerializable" wrapper for "CMatrixFloat".
TMatchingMethod matching_method
Matching method.
void loadFromConfigFile(const mrpt::utils::CConfigFileBase &source, const std::string §ion) MRPT_OVERRIDE
This method load the options from a ".ini"-like file or memory-stored string list.
GLubyte GLubyte GLubyte a
void VISION_IMPEXP normalizeImage(const mrpt::utils::CImage &image, mrpt::utils::CImage &nimage)
Normalizes the brigthness and contrast of an image by setting its mean value to zero and its standard...
GLenum const GLfloat * params
size_t getWidth() const MRPT_OVERRIDE
Returns the width of the image in pixels.
mrpt::math::CMatrixDouble33 VISION_IMPEXP defaultIntrinsicParamsMatrix(unsigned int camIndex=0, unsigned int resolutionX=320, unsigned int resolutionY=240)
Returns the stored, default intrinsic params matrix for a given camera:
A structure for holding correspondences between two sets of points or points-like entities in 2D or 3...
void getHomogeneousMatrix(mrpt::math::CMatrixDouble44 &out_HM) const
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (t...
EIGEN_STRONG_INLINE double mean() const
Computes the mean of the entire matrix.
mrpt::poses::CPose3DQuat rightCameraPose
Pose of the right camera with respect to the coordinate origin of the left camera.
virtual int printf(const char *fmt,...) MRPT_printf_format_check(2
Writes a string to the stream in a textual form.
struct VISION_IMPEXP mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks landmarks
Structure to hold the parameters of a pinhole camera model.
Uncertainty propagation through the Scaled Unscented Transformation.
size_t getHeight() const MRPT_OVERRIDE
Returns the height of the image in pixels.
float stdDisp
Standard deviation of the error in disparity computation.
TLandmarkID ID
An ID for the landmark (see details next...) This ID was introduced in the version 3 of this class (2...
TMeasurementList sensedData
The list of observed ranges:
mrpt::math::CMatrixDouble33 K
Intrinsic parameters.
GLdouble GLdouble GLint GLint GLdouble GLdouble GLint GLint GLdouble w1
2D line without bounds, represented by its equation .
mrpt::math::CMatrixDouble33 VISION_IMPEXP buildIntrinsicParamsMatrix(const double focalLengthX, const double focalLengthY, const double centerX, const double centerY)
Builds the intrinsic parameters matrix A from parameters:
mrpt::math::CMatrixDouble33 covariance
The covariance matrix of the landmark, with variable indices [0,1,2] being [range,yaw,pitch].