kalman_imu_data.cpp
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 ***************************************************************************************************/
33 #include "ros/ros.h"
34 #include "std_msgs/String.h"
35 #include <sstream>
36 #include <string>
37 #include <iostream>
38 #include <math.h>
39 #include <cmath>
40 #include <vector>
41 
42 #include <boost/format.hpp>
43 #include <kfilter/ekfilter.hpp>
44 #include <kfilter/kvector.hpp>
45 
46 //messages
47 
48 #include <imu_network/sensors_network.h>
49 #include <imu_network/filtered_imu_network.h>
50 #include <imu_network/filtered_imu.h>
51 
52 
53 #define MAX_MEAN_IT 64 //number of iterations to measure the mean values from gyroscopes
54 
55 #define GYRO_CONVERT M_PI/180*0.069565 // conversion of gyro's values from ADC to rad/sec
56 using namespace std;
57 
58 ros::NodeHandle* n;
59 ros::Publisher chatter_pub;
60 
61 
62 class imuEKF_sp : public Kalman::EKFilter<double,0,false,false,false>
63 {
64  public:
65 
67  {
68  setDim(6, 0, 6, 3, 3);
69  Period = 0.025;
70  }
71 
72  protected:
73 
74  void makeA()
75  {
76  for (int i = 0 ; i<6 ; i++)
77  {
78  for(int j = 0 ; j<6 ; j++)
79  {
80  if(i==j) A(i,j)=1.0;
81  else A(i,j) = 0.0;
82  }
83  }
84  A(0,1) = Period;
85  A(2,3) = Period;
86  A(4,5) = Period;
87 
88  }
89  void makeH()
90  {
91  for(int i=0;i<3;i++)
92  {
93  for(int j=0;j<6;j++)
94  {
95  H(i,j)=0.0;
96  }
97  }
98  H(0,1)=1.0;
99  H(1,3)=1.0;
100  H(2,5)=1.0;
101 
102  }
103  void makeV()
104  {
105  for(int i=0;i<3;i++)
106  {
107  for(int j=0;j<3;j++)
108  {
109  if(i==j) V(i,j)=1.0;
110  else V(i,j)=0.0;
111  }
112  }
113 
114  }
115  void makeR()
116  {
117  for(int i=0;i<3;i++)
118  {
119  for(int j=0;j<3;j++)
120  {
121  if(i==j) R(i,j)=75*M_PI/180; // 75 dps in rad/s
122  else R(i,j)=0.0;
123  }
124  }
125 
126  }
127  void makeW()
128  {
129 
130  for(int i=0;i<6;i++)
131  {
132  for(int j=0;j<6;j++)
133  {
134  if(i==j) W(i,j) = 1.0;
135  else W(i,j) = 0.0;
136  }
137  }
138 
139  }
140  void makeQ()
141  {
142  for(int i=0;i<6;i++)
143  {
144  for(int j=0;j<6;j++)
145  {
146  if(i==j) Q(i,j) = 1.0;
147  else Q(i,j) = 0.0;
148  }
149  }
150 
151  }
152  void makeProcess()
153  {
154  Vector x_(x.size());
155  x_(0) = x(0) + x(1)*Period;
156  x_(1) = x(1);
157  x_(2) = x(2) + x(3)*Period;
158  x_(3) = x(3);
159  x_(4) = x(0) + x(5)*Period;
160  x_(5) = x(5);
161 
162  x.swap(x_);
163  }
164  void makeMeasure()
165  {
166  Vector z(3);
167  z(0)=x(1);
168  z(1)=x(3);
169  z(2)=x(5);
170  }
171 
172  double Period;
173 
174 };
175 
176 vector<imuEKF_sp> kalman_imu;
177 
178 imuEKF_sp::Vector _z(3);
179 imuEKF_sp::Vector _u;
180 
181 vector<ros::Time>time_stamp;
182 vector<float>gyro_valx;
183 vector<float>gyro_valy;
184 vector<float>gyro_valz;
185 
186 vector<float>gyro_mean_vect[MAX_MEAN_IT][3]; //vectors for allocation of values of gyro for mean
187 vector<float>gyro_real_mean[3]; //vetor of gyro's means
188 
189 
190 
192 int first_run=0;
194 int mean_it = 0;
195 
196 imu_network::filtered_imu_network kalman_data_network;
197 
198 void chatterCallback(const imu_network::sensors_network::ConstPtr& msg)
199 {
200  if(first_run ==0)
201  {
202 
203  sensors_number=(int)msg->sensors_val[0].total_number;
204 
205  for (int i=0;i<sensors_number;i++)
206  {
207  //published message initialization
208  imu_network::filtered_imu kalman_imu_data;
209  kalman_data_network.filtered_imu_network.push_back(kalman_imu_data);
210 
211  time_stamp.push_back(msg->sensors_val[i].header.stamp);
212  gyro_valx.push_back(msg->sensors_val[i].S_Gx*GYRO_CONVERT);
213  gyro_valy.push_back(msg->sensors_val[i].S_Gy*GYRO_CONVERT);
214  gyro_valz.push_back(msg->sensors_val[i].S_Gz*GYRO_CONVERT);
215 
216  imuEKF_sp kalman_initializer;
217  kalman_imu.push_back(kalman_initializer);
218 
219  imuEKF_sp::Vector _x(6);
220 
221  imuEKF_sp::Matrix _P0(6,6);
222 
223  _x(0)=0.0;
224  _x(1)=0.0;
225  _x(2)=0.0;
226  _x(3)=0.0;
227  _x(4)=0.0;
228  _x(5)=0.0;
229 
230  for (int a = 0; a<6;a++)
231  {
232  for (int b=0;b<6;b++)
233  {
234  if (a==b) _P0(a,b)=10.3;
235  else _P0(a,b)=0.0;
236  }
237  }
238  kalman_imu[i].init(_x,_P0);
239  }
240  first_run = 1 ;
241  return;
242  }
243 
244  imuEKF_sp::Vector _x(6);
245 
246  if(mean_it<MAX_MEAN_IT)
247  {
248  for(int i= 0;i<sensors_number;i++)
249  {
250  gyro_mean_vect[i][0].push_back(msg->sensors_val[i].S_Gx);
251  gyro_mean_vect[i][1].push_back(msg->sensors_val[i].S_Gy);
252  gyro_mean_vect[i][2].push_back(msg->sensors_val[i].S_Gz);
253  gyro_real_mean[0].push_back(i);
254  gyro_real_mean[1].push_back(i);
255  gyro_real_mean[2].push_back(i);
256  }
257  mean_it++;
258  return;
259  }
260  //getting gyros's means to compensate it (if it's needed!)
261  if(mean_it==MAX_MEAN_IT)
262  {
263  for(int i= 0;i<sensors_number;i++)
264  {
265  for(int j=0;j<mean_it;j++)
266  {
267  gyro_real_mean[0][i]+=gyro_mean_vect[i][0][j];
268  gyro_real_mean[1][i]+=gyro_mean_vect[i][1][j];
269  gyro_real_mean[2][i]+=gyro_mean_vect[i][2][j];
270  }
274  cout<<"mean_it = "<<mean_it<<" i="<<i<<" gyro_real_mean(0)="<<gyro_real_mean[0][i]<<" gyro_real_mean(1)="<<gyro_real_mean[1][i]<<" gyro_real_mean(2)="<<gyro_real_mean[2][i]<<endl;
275  }
276  mean_it++;
277  }
278 
279  float sensor_var[sensors_number][9];
280 
281  for(int i = 0;i<sensors_number;i++)
282  {
283  sensor_var[i][0]=msg->sensors_val[i].S_Ax;
284  sensor_var[i][1]=msg->sensors_val[i].S_Ay;
285  sensor_var[i][2]=msg->sensors_val[i].S_Az;
286  sensor_var[i][3]=msg->sensors_val[i].S_Mx;
287  sensor_var[i][4]=msg->sensors_val[i].S_My;
288  sensor_var[i][5]=msg->sensors_val[i].S_Mz;
289  sensor_var[i][6]=msg->sensors_val[i].S_Gx;
290  sensor_var[i][7]=msg->sensors_val[i].S_Gy;
291  sensor_var[i][8]=msg->sensors_val[i].S_Gz;
292 
293  _z(0)=(msg->sensors_val[i].S_Gx-gyro_real_mean[0][i])*GYRO_CONVERT;
294  _z(1)=(msg->sensors_val[i].S_Gy-gyro_real_mean[1][i])*GYRO_CONVERT;
295  _z(2)=(msg->sensors_val[i].S_Gz-gyro_real_mean[0][i])*GYRO_CONVERT;
296 
297  kalman_imu[i].step(_u,_z);
298 
299  imuEKF_sp::Vector result(6);
300  result = kalman_imu[i].getX();
301  //storing the values inside message variables...
302  kalman_data_network.filtered_imu_network[i].linear_acceleration_x = sensor_var[i][0];
303  kalman_data_network.filtered_imu_network[i].linear_acceleration_y = sensor_var[i][1];
304  kalman_data_network.filtered_imu_network[i].linear_acceleration_z = sensor_var[i][2];
305 
306  kalman_data_network.filtered_imu_network[i].angular_velocity_x = result(1);
307  kalman_data_network.filtered_imu_network[i].angular_velocity_y = result(3);
308  kalman_data_network.filtered_imu_network[i].angular_velocity_z = result(5);
309 
310  kalman_data_network.filtered_imu_network[i].angular_displacement_x = result(0);
311  kalman_data_network.filtered_imu_network[i].angular_displacement_y = result(2);
312  kalman_data_network.filtered_imu_network[i].angular_displacement_z = result(4);
313 
314  kalman_data_network.filtered_imu_network[i].magnetometer_x = sensor_var[i][3];
315  kalman_data_network.filtered_imu_network[i].magnetometer_y = sensor_var[i][4];
316  kalman_data_network.filtered_imu_network[i].magnetometer_z = sensor_var[i][5];
317 
318  kalman_data_network.filtered_imu_network[i].number= i;
319  kalman_data_network.filtered_imu_network[i].total_number=sensors_number;
320 
321  kalman_data_network.filtered_imu_network[i].algorithm = 0;
322 
323  kalman_data_network.filtered_imu_network[i].header.stamp = msg->sensors_val[i].header.stamp;
324  kalman_data_network.filtered_imu_network[i].header.frame_id = "filtered_imu_network";
325 
326  }
328 
329 }
330 
335 int main(int argc, char **argv)
336 {
337  ros::init(argc, argv, "kalman_imu_raw");
338  n = new(ros::NodeHandle);
339  ros::Subscriber sub = n->subscribe("topic_raw_data", 1000, chatterCallback);
340  chatter_pub = n->advertise<imu_network::filtered_imu_network>("topic_filtered_imu", 1000);
341 
342  ros::spin();
343 
344  return 0;
345 }
ros::Publisher chatter_pub
vector< float > gyro_valy
vector< imuEKF_sp > kalman_imu
vector< float > gyro_real_mean[3]
void chatterCallback(const imu_network::sensors_network::ConstPtr &msg)
#define MAX_MEAN_IT
void makeMeasure()
vector< float > gyro_mean_vect[MAX_MEAN_IT][3]
vector< ros::Time > time_stamp
imuEKF_sp::Vector _z(3)
ros::NodeHandle * n
int first_run
void makeProcess()
#define GYRO_CONVERT
imuEKF_sp::Vector _u
int mean_it
int main(int argc, char **argv)
vector< float > gyro_valz
int marker_id
imu_network::filtered_imu_network kalman_data_network
int sensors_number
vector< float > gyro_valx


imu_network
Author(s): Telmo Rafeiro
autogenerated on Mon Mar 2 2015 01:31:44