odometry.h
Go to the documentation of this file.
1 /**************************************************************************************************
2  Software License Agreement (BSD License)
3 
4  Copyright (c) 2011-2013, LAR toolkit developers - University of Aveiro - http://lars.mec.ua.pt
5  All rights reserved.
6 
7  Redistribution and use in source and binary forms, with or without modification, are permitted
8  provided that the following conditions are met:
9 
10  *Redistributions of source code must retain the above copyright notice, this list of
11  conditions and the following disclaimer.
12  *Redistributions in binary form must reproduce the above copyright notice, this list of
13  conditions and the following disclaimer in the documentation and/or other materials provided
14  with the distribution.
15  *Neither the name of the University of Aveiro nor the names of its contributors may be used to
16  endorse or promote products derived from this software without specific prior written permission.
17 
18  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR
19  IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND
20  FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR
21  CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
22  DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
23  DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER
24  IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT
25  OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 ***************************************************************************************************/
31 #include <iostream>
32 #include <ros/ros.h>
33 
34 #include <tf/transform_broadcaster.h>
35 #include <nav_msgs/Odometry.h>
36 #include <kfilter/ekfilter.hpp>
37 
38 #define DEFAULT_WHEEL_BASE 2.5
39 
40 #include <signal.h>
41 
42 #include <atlascar_base/AtlascarStatus.h>
43 #include <atlascar_base/AtlascarVelocityStatus.h>
44 using namespace ros;
45 using namespace std;
46 using namespace Kalman;
47 
48 void IncommingDataHandler(int);
49 // bool ConvertEstimatedToMeasurment(double vl,double dir,double*dx,double*dy,double*dtheta,double dt,double l,double bwa);
50 
51 class non_holonomic_ekfilter: public Kalman::EKFilter<double,1,false,false,true>
52 {
53  public:
55  {
56  setDim(5,0,5,2,2);
57 
58  Vector x_0(5);
59  double _P0[25];
60 
61  memset(_P0,0,sizeof(_P0));
62 
63  _P0[0]=1*1;
64  _P0[6]=1*1;
65  _P0[12]=0.1*1;
66  _P0[18]=100*100;
67  _P0[24]=100*100;
68 
69  x_0(1)=0;
70  x_0(2)=0;
71  x_0(3)=0;
72  x_0(4)=0;
73  x_0(5)=0;
74 
75 
76  Matrix P0(5,5,_P0);
77 
78  cout<<"P0 "<<P0<<endl;
79  cout<<"x_0 "<<x_0<<endl;
80 
81  init(x_0,P0);
82 
83 
84  }
85 
86 
87  void SetWheelBase(double l_)
88  {
89  l=l_;
90 
91  }
92 
93  void SetTimeInterval(double dt_)
94  {
95  dt=dt_;
96  }
97 
98 
99 
100  protected:
101 
102  double l,dt;
103  void makeA()
104  {
105  double vl=x(4);
106  double yaw=x(3);
107  double phi=x(5);
108 
109  A(1,1)=1.0;
110  A(1,2)=0.0;
111  A(1,3)=-sin(yaw)*cos(phi)*vl*dt;
112  A(1,4)=cos(yaw)*cos(phi)*dt;
113  A(1,5)=cos(yaw)*(-sin(phi))*vl*dt;
114 
115 
116  A(2,1)=0.0;
117  A(2,2)=1.0;
118  A(2,3)=cos(yaw)*cos(phi)*vl*dt;
119  A(2,4)=sin(yaw)*cos(phi)*dt;
120  A(2,5)=sin(yaw)*(-sin(phi))*vl*dt;
121 
122  A(3,1)=0.0;
123  A(3,2)=0.0;
124  A(3,3)=1.0;
125  //A(3,4)=sin(phi/l)*dt; //erro no l
126  A(3,4)=sin(phi)*(dt/l);
127  //A(3,5)=cos(phi/l)*vl*dt/l; //erro no l
128  A(3,5)=cos(phi)*vl*dt/l;
129 
130  A(4,1)=0.0;
131  A(4,2)=0.0;
132  A(4,3)=0.0;
133  A(4,4)=1.0;
134  A(4,5)=0.0;
135 
136  A(5,1)=0.0;
137  A(5,2)=0.0;
138  A(5,3)=0.0;
139  A(5,4)=0.0;
140  A(5,5)=1.0;
141 
142 
143 
144  }
145  void makeH()
146  {
147 
148  H(1,1) = 0.0;
149  H(1,2) = 0.0;
150  H(1,3) = 0.0;
151  H(1,4) = 1.0;
152  H(1,5) = 0.0;
153 
154  H(2,1) = 0.0;
155  H(2,2) = 0.0;
156  H(2,3) = 0.0;
157  H(2,4) = 0.0;
158  H(2,5) = 1.0;
159 
160 
161 
162  }
163  void makeW()
164  {
165  W(1,1) = 1.0;
166  W(1,2) = 0.0;
167  W(1,3) = 0.0;
168  W(1,4) = 0.0;
169  W(1,5) = 0.0;
170 
171  W(2,1) = 0.0;
172  W(2,2) = 1.0;
173  W(2,3) = 0.0;
174  W(2,4) = 0.0;
175  W(2,5) = 0.0;
176 
177  W(3,1) = 0.0;
178  W(3,2) = 0.0;
179  W(3,3) = 1.0;
180  W(3,4) = 0.0;
181  W(3,5) = 0.0;
182 
183  W(4,1) = 0.0;
184  W(4,2) = 0.0;
185  W(4,3) = 0.0;
186  W(4,4) = 1.0;
187  W(4,5) = 0.0;
188 
189 
190  W(5,1) = 0.0;
191  W(5,2) = 0.0;
192  W(5,3) = 0.0;
193  W(5,4) = 0.0;
194  W(5,5) = 1.0;
195 
196  }
197  void makeV()
198  {
199  V(1,1) = 1.0;
200  V(1,2) = 0.0;
201  V(2,1) = 0.0;
202  V(2,2) = 1.0;
203  }
204 
205  void makeR()
206  {
207 // R(1,1) = 0.1;//vel
208  R(1,1) =0.00121;
209 
210  R(1,2) = 0.0;
211 
212  R(2,1) = 0.0;
213  R(2,2) = 0.003106;//dir
214 // R(2,2) = 0.01;
215 
216  }
217 
218  void makeQ()
219  {
220  //X
221 // double q=0.001;
222  Q(1,1) = 0.000001;
223  Q(1,2) = 0.0;
224  Q(1,3) = 0.0;
225  Q(1,4) = 0.0;
226  Q(1,5) = 0.0;
227 
228 
229  //Y
230  Q(2,1) = 0.0;
231  Q(2,2) = 0.000001;
232  Q(2,3) = 0.0;
233  Q(2,4) = 0.0;
234  Q(2,5) = 0.0;
235 
236 
237  //yaw
238  Q(3,1) = 0.0;
239  Q(3,2) = 0.0;
240  Q(3,3) = 0.005;
241  Q(3,4) = 0.0;
242  Q(3,5) = 0.0;
243 
244 
245  //vl
246  Q(4,1) = 0.0;
247  Q(4,2) = 0.0;
248  Q(4,3) = 0.0;
249  Q(4,4) = 0.01;
250  Q(4,5) = 0.0;
251 
252 
253  //phi
254  Q(5,1) = 0.0;
255  Q(5,2) = 0.0;
256  Q(5,3) = 0.0;
257  Q(5,4) = 0.0;
258  Q(5,5) = 0.0005;
259 
260 
261  }
262 
263  void makeProcess()
264  {
265  Vector x_(x.size());
266  x_(1) = x(1) + cos(x(3))*cos(x(5))*x(4)*dt;
267  x_(2) = x(2) + sin(x(3))*cos(x(5))*x(4)*dt;
268  //x_(3) = x(3) + sin(x(5)/l)*x(4)*dt; //possivel erro no l
269  x_(3) = x(3) + sin(x(5))*(x(4)/l)*dt; //possivel erro no l
270  x_(4) = x(4);
271  x_(5) = x(5);
272  x.swap(x_);
273  }
274 
275  void makeMeasure()
276  {
277  z(1)=x(4); //velocidade
278  z(2)=x(5); // phi - angulo das rodas
279  }
280 };
281 
282 
void IncommingDataHandler(int)
void SetWheelBase(double l_)
Definition: odometry.h:87
non_holonomic_ekfilter::Matrix Matrix
Definition: odometry.h:284
void SetTimeInterval(double dt_)
Definition: odometry.h:93
non_holonomic_ekfilter::Vector Vector
Definition: odometry.h:283


atlascar_base
Author(s): Jorge Almeida, Sérgio Pinho, Miguel Oliveira, Pedro Salvado, Andre Oliveira and Pedro Pinheiro
autogenerated on Mon Mar 2 2015 01:31:23