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
00031 #include <iostream>
00032 #include <ros/ros.h>
00033
00034 #include <tf/transform_broadcaster.h>
00035 #include <nav_msgs/Odometry.h>
00036 #include <kfilter/ekfilter.hpp>
00037
00038 #define DEFAULT_WHEEL_BASE 2.5
00039
00040 #include <signal.h>
00041
00042 #include <atlascar_base/AtlascarStatus.h>
00043 #include <atlascar_base/AtlascarVelocityStatus.h>
00044 using namespace ros;
00045 using namespace std;
00046 using namespace Kalman;
00047
00048 void IncommingDataHandler(int);
00049
00050
00051 class non_holonomic_ekfilter: public Kalman::EKFilter<double,1,false,false,true>
00052 {
00053 public:
00054 non_holonomic_ekfilter()
00055 {
00056 setDim(5,0,5,2,2);
00057
00058 Vector x_0(5);
00059 double _P0[25];
00060
00061 memset(_P0,0,sizeof(_P0));
00062
00063 _P0[0]=1*1;
00064 _P0[6]=1*1;
00065 _P0[12]=0.1*1;
00066 _P0[18]=100*100;
00067 _P0[24]=100*100;
00068
00069 x_0(1)=0;
00070 x_0(2)=0;
00071 x_0(3)=0;
00072 x_0(4)=0;
00073 x_0(5)=0;
00074
00075
00076 Matrix P0(5,5,_P0);
00077
00078 cout<<"P0 "<<P0<<endl;
00079 cout<<"x_0 "<<x_0<<endl;
00080
00081 init(x_0,P0);
00082
00083
00084 }
00085
00086
00087 void SetWheelBase(double l_)
00088 {
00089 l=l_;
00090
00091 }
00092
00093 void SetTimeInterval(double dt_)
00094 {
00095 dt=dt_;
00096 }
00097
00098
00099
00100 protected:
00101
00102 double l,dt;
00103 void makeA()
00104 {
00105 double vl=x(4);
00106 double yaw=x(3);
00107 double phi=x(5);
00108
00109 A(1,1)=1.0;
00110 A(1,2)=0.0;
00111 A(1,3)=-sin(yaw)*cos(phi)*vl*dt;
00112 A(1,4)=cos(yaw)*cos(phi)*dt;
00113 A(1,5)=cos(yaw)*(-sin(phi))*vl*dt;
00114
00115
00116 A(2,1)=0.0;
00117 A(2,2)=1.0;
00118 A(2,3)=cos(yaw)*cos(phi)*vl*dt;
00119 A(2,4)=sin(yaw)*cos(phi)*dt;
00120 A(2,5)=sin(yaw)*(-sin(phi))*vl*dt;
00121
00122 A(3,1)=0.0;
00123 A(3,2)=0.0;
00124 A(3,3)=1.0;
00125
00126 A(3,4)=sin(phi)*(dt/l);
00127
00128 A(3,5)=cos(phi)*vl*dt/l;
00129
00130 A(4,1)=0.0;
00131 A(4,2)=0.0;
00132 A(4,3)=0.0;
00133 A(4,4)=1.0;
00134 A(4,5)=0.0;
00135
00136 A(5,1)=0.0;
00137 A(5,2)=0.0;
00138 A(5,3)=0.0;
00139 A(5,4)=0.0;
00140 A(5,5)=1.0;
00141
00142
00143
00144 }
00145 void makeH()
00146 {
00147
00148 H(1,1) = 0.0;
00149 H(1,2) = 0.0;
00150 H(1,3) = 0.0;
00151 H(1,4) = 1.0;
00152 H(1,5) = 0.0;
00153
00154 H(2,1) = 0.0;
00155 H(2,2) = 0.0;
00156 H(2,3) = 0.0;
00157 H(2,4) = 0.0;
00158 H(2,5) = 1.0;
00159
00160
00161
00162 }
00163 void makeW()
00164 {
00165 W(1,1) = 1.0;
00166 W(1,2) = 0.0;
00167 W(1,3) = 0.0;
00168 W(1,4) = 0.0;
00169 W(1,5) = 0.0;
00170
00171 W(2,1) = 0.0;
00172 W(2,2) = 1.0;
00173 W(2,3) = 0.0;
00174 W(2,4) = 0.0;
00175 W(2,5) = 0.0;
00176
00177 W(3,1) = 0.0;
00178 W(3,2) = 0.0;
00179 W(3,3) = 1.0;
00180 W(3,4) = 0.0;
00181 W(3,5) = 0.0;
00182
00183 W(4,1) = 0.0;
00184 W(4,2) = 0.0;
00185 W(4,3) = 0.0;
00186 W(4,4) = 1.0;
00187 W(4,5) = 0.0;
00188
00189
00190 W(5,1) = 0.0;
00191 W(5,2) = 0.0;
00192 W(5,3) = 0.0;
00193 W(5,4) = 0.0;
00194 W(5,5) = 1.0;
00195
00196 }
00197 void makeV()
00198 {
00199 V(1,1) = 1.0;
00200 V(1,2) = 0.0;
00201 V(2,1) = 0.0;
00202 V(2,2) = 1.0;
00203 }
00204
00205 void makeR()
00206 {
00207
00208 R(1,1) =0.00121;
00209
00210 R(1,2) = 0.0;
00211
00212 R(2,1) = 0.0;
00213 R(2,2) = 0.003106;
00214
00215
00216 }
00217
00218 void makeQ()
00219 {
00220
00221
00222 Q(1,1) = 0.000001;
00223 Q(1,2) = 0.0;
00224 Q(1,3) = 0.0;
00225 Q(1,4) = 0.0;
00226 Q(1,5) = 0.0;
00227
00228
00229
00230 Q(2,1) = 0.0;
00231 Q(2,2) = 0.000001;
00232 Q(2,3) = 0.0;
00233 Q(2,4) = 0.0;
00234 Q(2,5) = 0.0;
00235
00236
00237
00238 Q(3,1) = 0.0;
00239 Q(3,2) = 0.0;
00240 Q(3,3) = 0.005;
00241 Q(3,4) = 0.0;
00242 Q(3,5) = 0.0;
00243
00244
00245
00246 Q(4,1) = 0.0;
00247 Q(4,2) = 0.0;
00248 Q(4,3) = 0.0;
00249 Q(4,4) = 0.01;
00250 Q(4,5) = 0.0;
00251
00252
00253
00254 Q(5,1) = 0.0;
00255 Q(5,2) = 0.0;
00256 Q(5,3) = 0.0;
00257 Q(5,4) = 0.0;
00258 Q(5,5) = 0.0005;
00259
00260
00261 }
00262
00263 void makeProcess()
00264 {
00265 Vector x_(x.size());
00266 x_(1) = x(1) + cos(x(3))*cos(x(5))*x(4)*dt;
00267 x_(2) = x(2) + sin(x(3))*cos(x(5))*x(4)*dt;
00268
00269 x_(3) = x(3) + sin(x(5))*(x(4)/l)*dt;
00270 x_(4) = x(4);
00271 x_(5) = x(5);
00272 x.swap(x_);
00273 }
00274
00275 void makeMeasure()
00276 {
00277 z(1)=x(4);
00278 z(2)=x(5);
00279 }
00280 };
00281
00282
00283 typedef non_holonomic_ekfilter::Vector Vector;
00284 typedef non_holonomic_ekfilter::Matrix Matrix;