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
00033 #include "ros/ros.h"
00034 #include "std_msgs/String.h"
00035 #include <sstream>
00036 #include <string>
00037 #include <iostream>
00038 #include <math.h>
00039 #include <cmath>
00040 #include <vector>
00041
00042 #include <boost/format.hpp>
00043 #include <kfilter/ekfilter.hpp>
00044 #include <kfilter/kvector.hpp>
00045
00046
00047
00048 #include <imu_network/sensors_network.h>
00049 #include <imu_network/filtered_imu_network.h>
00050 #include <imu_network/filtered_imu.h>
00051
00052
00053 #define MAX_MEAN_IT 64 //number of iterations to measure the mean values from gyroscopes
00054
00055 #define GYRO_CONVERT M_PI/180*0.069565 // conversion of gyro's values from ADC to rad/sec
00056 using namespace std;
00057
00058 ros::NodeHandle* n;
00059 ros::Publisher chatter_pub;
00060
00061
00062 class imuEKF_sp : public Kalman::EKFilter<double,0,false,false,false>
00063 {
00064 public:
00065
00066 imuEKF_sp()
00067 {
00068 setDim(6, 0, 6, 3, 3);
00069 Period = 0.025;
00070 }
00071
00072 protected:
00073
00074 void makeA()
00075 {
00076 for (int i = 0 ; i<6 ; i++)
00077 {
00078 for(int j = 0 ; j<6 ; j++)
00079 {
00080 if(i==j) A(i,j)=1.0;
00081 else A(i,j) = 0.0;
00082 }
00083 }
00084 A(0,1) = Period;
00085 A(2,3) = Period;
00086 A(4,5) = Period;
00087
00088 }
00089 void makeH()
00090 {
00091 for(int i=0;i<3;i++)
00092 {
00093 for(int j=0;j<6;j++)
00094 {
00095 H(i,j)=0.0;
00096 }
00097 }
00098 H(0,1)=1.0;
00099 H(1,3)=1.0;
00100 H(2,5)=1.0;
00101
00102 }
00103 void makeV()
00104 {
00105 for(int i=0;i<3;i++)
00106 {
00107 for(int j=0;j<3;j++)
00108 {
00109 if(i==j) V(i,j)=1.0;
00110 else V(i,j)=0.0;
00111 }
00112 }
00113
00114 }
00115 void makeR()
00116 {
00117 for(int i=0;i<3;i++)
00118 {
00119 for(int j=0;j<3;j++)
00120 {
00121 if(i==j) R(i,j)=75*M_PI/180;
00122 else R(i,j)=0.0;
00123 }
00124 }
00125
00126 }
00127 void makeW()
00128 {
00129
00130 for(int i=0;i<6;i++)
00131 {
00132 for(int j=0;j<6;j++)
00133 {
00134 if(i==j) W(i,j) = 1.0;
00135 else W(i,j) = 0.0;
00136 }
00137 }
00138
00139 }
00140 void makeQ()
00141 {
00142 for(int i=0;i<6;i++)
00143 {
00144 for(int j=0;j<6;j++)
00145 {
00146 if(i==j) Q(i,j) = 1.0;
00147 else Q(i,j) = 0.0;
00148 }
00149 }
00150
00151 }
00152 void makeProcess()
00153 {
00154 Vector x_(x.size());
00155 x_(0) = x(0) + x(1)*Period;
00156 x_(1) = x(1);
00157 x_(2) = x(2) + x(3)*Period;
00158 x_(3) = x(3);
00159 x_(4) = x(0) + x(5)*Period;
00160 x_(5) = x(5);
00161
00162 x.swap(x_);
00163 }
00164 void makeMeasure()
00165 {
00166 Vector z(3);
00167 z(0)=x(1);
00168 z(1)=x(3);
00169 z(2)=x(5);
00170 }
00171
00172 double Period;
00173
00174 };
00175
00176 vector<imuEKF_sp> kalman_imu;
00177
00178 imuEKF_sp::Vector _z(3);
00179 imuEKF_sp::Vector _u;
00180
00181 vector<ros::Time>time_stamp;
00182 vector<float>gyro_valx;
00183 vector<float>gyro_valy;
00184 vector<float>gyro_valz;
00185
00186 vector<float>gyro_mean_vect[MAX_MEAN_IT][3];
00187 vector<float>gyro_real_mean[3];
00188
00189
00190
00191 int sensors_number;
00192 int first_run=0;
00193 int marker_id;
00194 int mean_it = 0;
00195
00196 imu_network::filtered_imu_network kalman_data_network;
00197
00198 void chatterCallback(const imu_network::sensors_network::ConstPtr& msg)
00199 {
00200 if(first_run ==0)
00201 {
00202
00203 sensors_number=(int)msg->sensors_val[0].total_number;
00204
00205 for (int i=0;i<sensors_number;i++)
00206 {
00207
00208 imu_network::filtered_imu kalman_imu_data;
00209 kalman_data_network.filtered_imu_network.push_back(kalman_imu_data);
00210
00211 time_stamp.push_back(msg->sensors_val[i].header.stamp);
00212 gyro_valx.push_back(msg->sensors_val[i].S_Gx*GYRO_CONVERT);
00213 gyro_valy.push_back(msg->sensors_val[i].S_Gy*GYRO_CONVERT);
00214 gyro_valz.push_back(msg->sensors_val[i].S_Gz*GYRO_CONVERT);
00215
00216 imuEKF_sp kalman_initializer;
00217 kalman_imu.push_back(kalman_initializer);
00218
00219 imuEKF_sp::Vector _x(6);
00220
00221 imuEKF_sp::Matrix _P0(6,6);
00222
00223 _x(0)=0.0;
00224 _x(1)=0.0;
00225 _x(2)=0.0;
00226 _x(3)=0.0;
00227 _x(4)=0.0;
00228 _x(5)=0.0;
00229
00230 for (int a = 0; a<6;a++)
00231 {
00232 for (int b=0;b<6;b++)
00233 {
00234 if (a==b) _P0(a,b)=10.3;
00235 else _P0(a,b)=0.0;
00236 }
00237 }
00238 kalman_imu[i].init(_x,_P0);
00239 }
00240 first_run = 1 ;
00241 return;
00242 }
00243
00244 imuEKF_sp::Vector _x(6);
00245
00246 if(mean_it<MAX_MEAN_IT)
00247 {
00248 for(int i= 0;i<sensors_number;i++)
00249 {
00250 gyro_mean_vect[i][0].push_back(msg->sensors_val[i].S_Gx);
00251 gyro_mean_vect[i][1].push_back(msg->sensors_val[i].S_Gy);
00252 gyro_mean_vect[i][2].push_back(msg->sensors_val[i].S_Gz);
00253 gyro_real_mean[0].push_back(i);
00254 gyro_real_mean[1].push_back(i);
00255 gyro_real_mean[2].push_back(i);
00256 }
00257 mean_it++;
00258 return;
00259 }
00260
00261 if(mean_it==MAX_MEAN_IT)
00262 {
00263 for(int i= 0;i<sensors_number;i++)
00264 {
00265 for(int j=0;j<mean_it;j++)
00266 {
00267 gyro_real_mean[0][i]+=gyro_mean_vect[i][0][j];
00268 gyro_real_mean[1][i]+=gyro_mean_vect[i][1][j];
00269 gyro_real_mean[2][i]+=gyro_mean_vect[i][2][j];
00270 }
00271 gyro_real_mean[0][i]/=MAX_MEAN_IT;
00272 gyro_real_mean[1][i]/=MAX_MEAN_IT;
00273 gyro_real_mean[2][i]/=MAX_MEAN_IT;
00274 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;
00275 }
00276 mean_it++;
00277 }
00278
00279 float sensor_var[sensors_number][9];
00280
00281 for(int i = 0;i<sensors_number;i++)
00282 {
00283 sensor_var[i][0]=msg->sensors_val[i].S_Ax;
00284 sensor_var[i][1]=msg->sensors_val[i].S_Ay;
00285 sensor_var[i][2]=msg->sensors_val[i].S_Az;
00286 sensor_var[i][3]=msg->sensors_val[i].S_Mx;
00287 sensor_var[i][4]=msg->sensors_val[i].S_My;
00288 sensor_var[i][5]=msg->sensors_val[i].S_Mz;
00289 sensor_var[i][6]=msg->sensors_val[i].S_Gx;
00290 sensor_var[i][7]=msg->sensors_val[i].S_Gy;
00291 sensor_var[i][8]=msg->sensors_val[i].S_Gz;
00292
00293 _z(0)=(msg->sensors_val[i].S_Gx-gyro_real_mean[0][i])*GYRO_CONVERT;
00294 _z(1)=(msg->sensors_val[i].S_Gy-gyro_real_mean[1][i])*GYRO_CONVERT;
00295 _z(2)=(msg->sensors_val[i].S_Gz-gyro_real_mean[0][i])*GYRO_CONVERT;
00296
00297 kalman_imu[i].step(_u,_z);
00298
00299 imuEKF_sp::Vector result(6);
00300 result = kalman_imu[i].getX();
00301
00302 kalman_data_network.filtered_imu_network[i].linear_acceleration_x = sensor_var[i][0];
00303 kalman_data_network.filtered_imu_network[i].linear_acceleration_y = sensor_var[i][1];
00304 kalman_data_network.filtered_imu_network[i].linear_acceleration_z = sensor_var[i][2];
00305
00306 kalman_data_network.filtered_imu_network[i].angular_velocity_x = result(1);
00307 kalman_data_network.filtered_imu_network[i].angular_velocity_y = result(3);
00308 kalman_data_network.filtered_imu_network[i].angular_velocity_z = result(5);
00309
00310 kalman_data_network.filtered_imu_network[i].angular_displacement_x = result(0);
00311 kalman_data_network.filtered_imu_network[i].angular_displacement_y = result(2);
00312 kalman_data_network.filtered_imu_network[i].angular_displacement_z = result(4);
00313
00314 kalman_data_network.filtered_imu_network[i].magnetometer_x = sensor_var[i][3];
00315 kalman_data_network.filtered_imu_network[i].magnetometer_y = sensor_var[i][4];
00316 kalman_data_network.filtered_imu_network[i].magnetometer_z = sensor_var[i][5];
00317
00318 kalman_data_network.filtered_imu_network[i].number= i;
00319 kalman_data_network.filtered_imu_network[i].total_number=sensors_number;
00320
00321 kalman_data_network.filtered_imu_network[i].algorithm = 0;
00322
00323 kalman_data_network.filtered_imu_network[i].header.stamp = msg->sensors_val[i].header.stamp;
00324 kalman_data_network.filtered_imu_network[i].header.frame_id = "filtered_imu_network";
00325
00326 }
00327 chatter_pub.publish(kalman_data_network);
00328
00329 }
00330
00335 int main(int argc, char **argv)
00336 {
00337 ros::init(argc, argv, "kalman_imu_raw");
00338 n = new(ros::NodeHandle);
00339 ros::Subscriber sub = n->subscribe("topic_raw_data", 1000, chatterCallback);
00340 chatter_pub = n->advertise<imu_network::filtered_imu_network>("topic_filtered_imu", 1000);
00341
00342 ros::spin();
00343
00344 return 0;
00345 }