Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011 #include "KeyPoint.h"
00012
00013 #include <string.h>
00014 #include <math.h>
00015
00016 #include "Workers/Math/Math.h"
00017 #include "Workers/Math/vec2.h"
00018
00019 #define THIS KeyPoint
00020
00021 using namespace std;
00022
00023 THIS::THIS ( float _x, float _y, float _scale, float _strength, int _sign, float _orientation, std::vector<double> _featureVector )
00024 {
00025 x = _x;
00026 y = _y;
00027 scale = _scale;
00028 strength = _strength;
00029 sign = _sign;
00030 orientation = _orientation;
00031 featureVector = _featureVector;
00032 vectorLimits.push_back(0);
00033 }
00034
00035 THIS::THIS ( float _x, float _y, float _scale, float _strength, int _sign )
00036 {
00037 x = _x;
00038 y = _y;
00039 scale = _scale;
00040 strength = _strength;
00041 sign = _sign;
00042 vectorLimits.push_back(0);
00043 }
00044
00045 THIS::THIS ( )
00046 {
00047 }
00048
00049 THIS::~THIS()
00050 {
00051 }
00052
00053 THIS::THIS ( const KeyPoint& other )
00054 {
00055 operator= ( other );
00056 }
00057
00058 THIS& THIS::operator= ( const KeyPoint & other )
00059 {
00060 if ( this == &other )
00061 {
00062 return *this;
00063 }
00064
00065 x = other.x;
00066 y = other.y;
00067 scale = other.scale;
00068 strength = other.strength;
00069 orientation = other.orientation;
00070 sign = other.sign;
00071 featureVector = other.featureVector;
00072 vectorLimits = other.vectorLimits;
00073 return *this;
00074 }
00075
00076 void THIS::addDescriptor( vector<double> descriptor )
00077 {
00078 featureVector.reserve( featureVector.size() + descriptor.size() );
00079 for ( unsigned i=0; i<descriptor.size(); i++ )
00080 {
00081 featureVector.push_back( descriptor[i] );
00082 }
00083
00084 vectorLimits.push_back( featureVector.size() );
00085 }
00086
00087 double THIS::squaredDistance ( const KeyPoint& other ) const
00088 {
00089 if ( featureVector.size() != other.featureVector.size() )
00090 {
00091 return 99999;
00092 }
00093
00094 double dist = 0;
00095 for ( unsigned n = 0; n < featureVector.size(); n++ )
00096 {
00097 double diff = featureVector[n] - other.featureVector[n];
00098 dist += diff * diff;
00099 }
00100
00101
00102
00103
00104
00105
00106
00107
00108
00109
00110 return dist;
00111 }
00112
00113
00114 double THIS::squaredDistance ( const KeyPoint& other, double max ) const
00115 {
00116 if ( featureVector.size() != other.featureVector.size() )
00117 {
00118 return 99999;
00119 }
00120
00121 double dist = 0;
00122 for ( unsigned n1 = 0; n1 < featureVector.size(); n1+=4 )
00123 {
00124 double diff;
00125
00126
00127 diff = featureVector[n1] - other.featureVector[n1];
00128 dist += diff * diff;
00129 diff = featureVector[n1+1] - other.featureVector[n1+1];
00130 dist += diff * diff;
00131 diff = featureVector[n1+2] - other.featureVector[n1+2];
00132 dist += diff * diff;
00133 diff = featureVector[n1+3] - other.featureVector[n1+3];
00134 dist += diff * diff;
00135
00136
00137 if ( dist >= max )
00138 {
00139 return dist;
00140 }
00141 }
00142
00143 return dist;
00144 }
00145
00146
00147 std::vector<Point2D> THIS::getBoundingBox() const
00148 {
00149 std::vector<Point2D> boxVertices ( 5 );
00150 float r = scale * 10.0 * sqrt ( 2 );
00151 for ( int j = 0; j < 5; j++ )
00152 {
00153 float alpha = ( float ( j ) + 0.5 ) / 4.0 * 2.0 * M_PI + orientation;
00154 boxVertices[j] = Point2D ( x + r * sin ( alpha ), y + r * cos ( alpha ) );
00155 }
00156 return boxVertices;
00157 }
00158
00159
00160 std::vector<Point2D> THIS::getCircle() const
00161 {
00162 float steps = 20;
00163 std::vector<Point2D> boxVertices ( steps+1 );
00164 float r = scale * 4.5/1.2 / 2.0;
00165 for ( int j = 0; j <= steps; j++ )
00166 {
00167 float alpha = ( float ( j ) + 0.5 ) / steps * 2.0 * M_PI + orientation;
00168 boxVertices[j] = Point2D ( x + r * sin ( alpha ), y + r * cos ( alpha ) );
00169 }
00170 return boxVertices;
00171 }
00172
00173
00174 std::vector<Point2D> THIS::getCenterArrow() const
00175 {
00176 std::vector<Point2D> arrowVertices ( 6 );
00177 const float r1 = scale * 5.0;
00178 const float r3 = r1 + 6.0;
00179 const float width = 3.0;
00180
00181 Point2D position ( x, y );
00182
00183 arrowVertices[0] = position;
00184 arrowVertices[1] = position + Point2D ( r1 * sin ( orientation ), r1 * cos ( orientation ) );
00185 arrowVertices[2] = arrowVertices[1] + CVec2 ( width * sin ( orientation + ( M_PI / 2.0 ) ), width * cos ( orientation + ( M_PI / 2.0 ) ) );
00186 arrowVertices[3] = position + Point2D ( r3 * sin ( orientation ), r3 * cos ( orientation ) );
00187 arrowVertices[4] = arrowVertices[1] - CVec2 ( width * sin ( orientation + ( M_PI / 2.0 ) ), width * cos ( orientation + ( M_PI / 2.0 ) ) );
00188 arrowVertices[5] = arrowVertices[1];
00189
00190 return arrowVertices;
00191 }
00192
00193
00194
00195
00196
00197
00198
00199
00200
00201
00202
00203
00204
00205
00206
00207
00208
00209
00210
00211
00212
00213
00214
00215
00216
00217
00218
00219
00220
00221
00222
00223
00224
00225
00226
00227
00228
00229
00230
00231
00232
00233
00234
00235
00236
00237 std::string THIS::toASCII()
00238 {
00239 ostringstream s;
00240 s << x << " " << y << " ";
00241
00242
00243
00244
00245 float r=scale*10;
00246 float a = 1/(r*r);
00247 float b = 0;
00248 float c = a;
00249
00250
00251
00252
00253 s << a << " " << b << " " << c << " ";
00254
00255 for ( unsigned i=0; i<featureVector.size(); i++ )
00256 {
00257 s << featureVector[i] << " ";
00258 }
00259
00260 return s.str();
00261 }
00262
00263 std::string THIS::toString()
00264 {
00265 ostringstream s;
00266 s << x << " " << y << " " << scale << " " << strength << " " << sign << " " << orientation << " ";
00267
00268 for ( unsigned i=0; i<featureVector.size(); i++ )
00269 {
00270 s << featureVector[i] << " ";
00271 }
00272
00273 return s.str();
00274 }
00275
00276 double THIS::calcIntersection( const KeyPoint& other )
00277 {
00278
00279 double R;
00280 double r;
00281
00282 if ( scale > other.scale )
00283 {
00284 R=scale*10;
00285 r=other.scale*10;
00286 }
00287 else
00288 {
00289 R=other.scale*10;
00290 r=scale*10;
00291 }
00292
00293 double d=sqrt( (other.x-x)*(other.x-x) + (other.y-y)*(other.y-y) );
00294
00295
00296 if ( d >= R+r )
00297 {
00298 return 0;
00299 }
00300
00301
00302 if ( d+r < R )
00303 {
00304 return M_PI*r*r;
00305 }
00306
00307
00308
00309 double a = (d*d + r*r - R*R) / ( 2*d*r );
00310 double b = (d*d + R*R - r*r) / ( 2*d*R );
00311 double c = (-d+r+R) * (d+r-R) * (d-r+R) * (d+r+R);
00312
00313 double A = r*r*acos( a ) + R*R*acos(b) - 0.5*sqrt(c);
00314
00315
00316
00317 return A;
00318 }
00319
00320 double THIS::calcOverlap( const KeyPoint& other )
00321 {
00322 double R=scale*10;
00323 double r=other.scale*10;
00324
00325 double areaInter = calcIntersection( other );
00326 double areaUnion = M_PI*R*R + M_PI*r*r - areaInter;
00327
00328 return areaInter / areaUnion;
00329 }
00330
00331 #undef THIS