00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00032 #include <mtt/types_declaration.h>
00033
00034 void constant_velocity_ekfilter::SetIdentity(Matrix& M,int size,double value)
00035 {
00036 for(int l=0;l<size;l++)
00037 for(int c=0;c<size;c++)
00038 if(c==l)
00039 M(l,c)=value;
00040 else
00041 M(l,c)=0;
00042 }
00043
00044 void constant_velocity_ekfilter::SetZero(Matrix& M,int size)
00045 {
00046 for(int l=0;l<size;l++)
00047 for(int c=0;c<size;c++)
00048 M(l,c)=0;
00049 }
00050
00051 void constant_velocity_ekfilter::InitFilter(Vector4d& x_init)
00052 {
00053 setDim(4,0,4,2,2);
00054 dt=0;
00055 lt=Time::now();
00056
00057 Vector x_0(4);
00058
00059 x_0(0)=x_init(0);
00060 x_0(1)=x_init(1);
00061 x_0(2)=x_init(2);
00062 x_0(3)=x_init(3);
00063
00064 Matrix P_0(4,4);
00065
00066 SetIdentity(P_0,4,10.);
00067
00068 init(x_0,P_0);
00069 }
00070
00071 void constant_velocity_ekfilter::makeCommonProcess()
00072 {
00073
00074
00075 dt=1./50.;
00076 }
00077
00078 void constant_velocity_ekfilter::makeBaseA()
00079 {
00080 A(0,0)=1.0;
00081 A(0,1)=0.0;
00082
00083 A(0,3)=0.0;
00084
00085 A(1,0)=0.0;
00086 A(1,1)=1.0;
00087 A(1,2)=0.0;
00088
00089
00090 A(2,0)=0.0;
00091 A(2,1)=0.0;
00092 A(2,2)=1.0;
00093 A(2,3)=0.0;
00094
00095 A(3,0)=0.0;
00096 A(3,1)=0.0;
00097 A(3,2)=0.0;
00098 A(3,3)=1.0;
00099 }
00100
00101 void constant_velocity_ekfilter::makeA()
00102 {
00103 A(0,2)=dt;
00104 A(1,3)=dt;
00105 }
00106
00107 void constant_velocity_ekfilter::makeBaseH()
00108 {
00109 H(0,0) = 1.0;
00110 H(1,1) = 1.0;
00111 }
00112
00113 void constant_velocity_ekfilter::makeBaseW()
00114 {
00115 SetIdentity(W,4,1.0);
00116 }
00117
00118 void constant_velocity_ekfilter::makeBaseV()
00119 {
00120 SetIdentity(V,2,1.0);
00121 }
00122
00123 void constant_velocity_ekfilter::makeR()
00124 {
00125 double dir = atan2(dz(1),dz(0));
00126
00127 Matrix2d eigval;
00128 Matrix2d eigvct;
00129
00130 double magnitude = sqrt(dz(1)*dz(1)+dz(0)*dz(0));
00131
00132
00133
00134
00135 double max_v=0.1;
00136 double min_v=0.005;
00137
00138 double nv = ((min_v - max_v)/max_v)*magnitude + max_v;
00139 nv=nv>min_v?nv:min_v;
00140
00141
00142
00143 eigval << max_v, 0,
00144 0, nv;
00145
00146 eigvct << 1, 0,
00147 0, 1;
00148
00149 Matrix2d rot;
00150 rot << cos(dir), sin(dir),
00151 -sin(dir), cos(dir);
00152
00153 eigvct= eigvct*rot;
00154
00155 Matrix2d cov = eigvct*eigval*eigvct.inverse();
00156
00157 R(0,0) = cov(0,0);
00158 R(0,1) = cov(0,1);
00159
00160 R(1,0) = cov(1,0);
00161 R(1,1) = cov(1,1);
00162 }
00163
00164 void constant_velocity_ekfilter::makeQ()
00165 {
00166 SetZero(Q,4);
00167 double sigma=10.;
00168 double factor=pow(sigma,2)*dt/6.;
00169
00170 Q(0,0)=factor*2*pow(dt,2);
00171 Q(1,1)=factor*2*pow(dt,2);
00172
00173 Q(0,2)=factor*3*pow(dt,1);
00174 Q(2,1)=factor*3*pow(dt,1);
00175
00176 Q(1,3)=factor*3*pow(dt,1);
00177 Q(3,1)=factor*3*pow(dt,1);
00178
00179 Q(2,2)=factor*6;
00180 Q(3,3)=factor*6;
00181 }
00182
00183 void constant_velocity_ekfilter::makeProcess()
00184 {
00185 Vector x_(x.size());
00186
00187 x_(0) = x(0) + x(2)*dt;
00188 x_(1) = x(1) + x(3)*dt;
00189 x_(2) = x(2);
00190 x_(3) = x(3);
00191
00192 x.swap(x_);
00193 }
00194
00195 void constant_velocity_ekfilter::makeMeasure()
00196 {
00197 z(0)=x(0);
00198 z(1)=x(1);
00199 }
00200
00201 t_point::t_point()
00202 {
00203 x=0;
00204 y=0;
00205 z=0;
00206 r=0;
00207 t=0;
00208 n=0;
00209 ni=0;
00210 }
00211
00212 void t_point::SetZero()
00213 {
00214 x=0;
00215 y=0;
00216 z=0;
00217 r=0;
00218 t=0;
00219 n=0;
00220 ni=0;
00221 }
00222
00223 t_point& t_point::operator+=(const t_point &rhs)
00224 {
00225 x+=rhs.x;
00226 y+=rhs.y;
00227 z+=rhs.z;
00228 r+=rhs.r;
00229 t+=rhs.t;
00230
00231 return *this;
00232 }
00233
00234 void t_point::Scale(double val)
00235 {
00236 x*=val;
00237 y*=val;
00238 z*=val;
00239 r*=val;
00240 t*=val;
00241 }
00242
00243
00244 t_cluster::t_cluster()
00245 {
00246 id=0;
00247
00248
00249
00250 }
00251
00252 t_cluster& t_cluster::operator=(const t_cluster &rhs)
00253 {
00254 id=rhs.id;
00255 centroid=rhs.centroid;
00256
00257 t_pointPtr p;
00258
00259 for(uint i=0;i<rhs.points.size();i++)
00260 {
00261 p.reset(new t_point);
00262 *p=*(rhs.points[i]);
00263
00264 points.push_back(p);
00265 }
00266
00267 return *this;
00268 }
00269
00270 bool t_cluster::BreakPointDetector(t_pointPtr&pt,t_pointPtr&pt_m1)
00271 {
00276 double d = sqrt( pow(pt->x-pt_m1->x,2) + pow(pt->y-pt_m1->y,2));
00277
00278 if(d>2.0)
00279 return true;
00280
00281 return false;
00282 }
00283
00284 void t_cluster::CalculateCentroid(void)
00285 {
00286 centroid.SetZero();
00287
00288 for(uint i=0;i<points.size();i++)
00289 centroid+=*points[i];
00290
00291 centroid.Scale(1./points.size());
00292 }
00293
00294
00295 void t_node::IncreaseAge(int increment)
00296 {
00297 age+=increment;
00298 }
00299
00300 void t_node::Step()
00301 {
00302 Vector u(0);
00303 Vector x_(4);
00304
00305
00306 Vector z_(2);
00307 z_(0)=z(0);
00308 z_(1)=z(1);
00309
00310
00311 estimator.step(u,z_);
00312
00313
00314 x_=estimator.getX();
00315
00316
00317 x(0)=x_(0);
00318 x(1)=x_(1);
00319 x(2)=x_(2);
00320 x(3)=x_(3);
00321
00322
00323 Matrix P_=estimator.calculateP();
00324
00325
00326 P(0,0)=P_(0,0);
00327 P(0,1)=P_(0,1);
00328 P(0,2)=P_(0,2);
00329 P(0,3)=P_(0,3);
00330
00331 P(1,0)=P_(1,0);
00332 P(1,1)=P_(1,1);
00333 P(1,2)=P_(1,2);
00334 P(1,3)=P_(1,3);
00335
00336 P(2,0)=P_(2,0);
00337 P(2,1)=P_(2,1);
00338 P(2,2)=P_(2,2);
00339 P(2,3)=P_(2,3);
00340
00341 P(3,0)=P_(3,0);
00342 P(3,1)=P_(3,1);
00343 P(3,2)=P_(3,2);
00344 P(3,3)=P_(3,3);
00345
00346
00347 Vector x_p_=estimator.predict(u);
00348
00349
00350 x_p(0)=x_p_(0);
00351 x_p(1)=x_p_(1);
00352 x_p(2)=x_p_(2);
00353 x_p(3)=x_p_(3);
00354 }
00355
00356 void t_node::CommonConstructor()
00357 {
00358
00359 Step();
00360 }
00361
00362 t_node::t_node(t_cluster&cluster,long iteration)
00363 {
00364 mode=NEW;
00365
00366 failed_associations_counter=0;
00367 successful_association_counter=1;
00368 age=0;
00369
00370 id=cluster.id;
00371 data_iteration=iteration;
00372
00373 local_cluster=cluster;
00374
00375 cluster.associations.push_back(id);
00376
00377 z(0)=local_cluster.centroid.x;
00378 z(1)=local_cluster.centroid.y;
00379
00380 Vector4d x_init;
00381
00382 x_init(0)=z(0);
00383 x_init(1)=z(1);
00384 x_init(2)=0;
00385 x_init(3)=0;
00386
00387 estimator.InitFilter(x_init);
00388
00389 CommonConstructor();
00390 }
00391
00392 t_node::t_node(t_node&node,t_cluster&cluster,long iteration)
00393 {
00394 mode=MAIN;
00395
00396 failed_associations_counter=node.failed_associations_counter;
00397 successful_association_counter=node.successful_association_counter+1;
00398 age=0;
00399
00400 id=node.id;
00401 data_iteration=iteration;
00402
00403 cluster.associations.push_back(id);
00404 local_cluster=cluster;
00405
00406 estimator=node.estimator;
00407
00408 z(0)=local_cluster.centroid.x;
00409 z(1)=local_cluster.centroid.y;
00410
00411 CommonConstructor();
00412 }
00413
00414 t_node::t_node(t_node&node,long iteration)
00415 {
00416 mode=FAILED;
00417
00418 failed_associations_counter=node.failed_associations_counter;
00419 failed_associations_counter++;
00420 age=0;
00421
00422 successful_association_counter=node.successful_association_counter;
00423
00424 id=node.id;
00425 data_iteration=iteration;
00426
00427 local_cluster=node.local_cluster;
00428
00429 estimator=node.estimator;
00430
00431
00432 z(0)=node.x_p(0);
00433 z(1)=node.x_p(1);
00434
00435 CommonConstructor();
00436 }
00437
00438 t_node::~t_node(void)
00439 {
00440
00441 }
00442
00443 string t_node::GetName()
00444 {
00445 return "N"+ boost::lexical_cast<string>(id) + ".(" + boost::lexical_cast<string>(data_iteration) + ")";
00446
00447 }
00448
00449 ostream& operator<< (ostream &o, const t_nodePtr &i)
00450 {
00451 return o << i->GetName();
00452
00453 }
00454