complementary_filter.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 ***************************************************************************************************/
27 
34 #include "ros/ros.h"
35 #include "std_msgs/String.h"
36 #include <sstream>
37 #include <string>
38 #include <iostream>
39 #include <math.h>
40 #include <cmath>
41 #include <vector>
42 
43 #include <boost/format.hpp>
44 
45 #include <imu_network/sensors_network.h>
46 #include <imu_network/filtered_imu_network.h>
47 #include <imu_network/filtered_imu.h>
48 
49 #define MAX_MEAN_IT 25 //number of iterations to measure the mean values from gyroscopes
50 
51 #define GYRO_CONVERT M_PI/180*0.069565 // conversion of gyro's values from ADC to rad/sec
52 
53 using namespace std;
54 
55 
56 ros::NodeHandle* n;
57 ros::Publisher chatter_pub;
58 
60 int first_run=0;
61 
62 vector<float>gyro_angle[3];
63 vector<float>accel_ang_x;
64 vector<float>accel_ang_y;
65 
66 vector<float>angle[3];
67 vector<float>angle_last_it[3];
68 
69 vector<float>gyro_mean_vect[MAX_MEAN_IT][3]; //vectors for allocation of values of gyro for mean
70 vector<float>gyro_real_mean[3]; //vetor of gyro's means
71 vector<float>gyro_last_it[3];
72 
73 float period = 1/7.35;
74 float alpha = 0.3;
75 float accel_alpha = 0.7;
76 
77 int mean_it = 0;
78 
79 imu_network::filtered_imu_network complementary_filter_network;
80 
81 void chatterCallback(const imu_network::sensors_network::ConstPtr& msg) //callback that intercept the sensor's raw data
82 {
83  float ax,ay,az;
84  if(first_run ==0)
85  {
86 
87  sensors_number=(int)msg->sensors_val[0].total_number;
88 
89  for (int i=0;i<sensors_number;i++)
90  {
91  //published message initialization
92  imu_network::filtered_imu filtered_imu_data;
93  complementary_filter_network.filtered_imu_network.push_back(filtered_imu_data);
94 
95  ax = msg->sensors_val[i].S_Ax;
96  ay = msg->sensors_val[i].S_Ay;
97  az = msg->sensors_val[i].S_Az;
98 
99  accel_ang_x.push_back(atan(ay/sqrt((ax*ax)+(az*az))));
100  accel_ang_y.push_back(atan(ax/sqrt((ay*ay)+(az*az))));
101 
102  gyro_angle[0].push_back(0);
103  gyro_angle[1].push_back(0);
104  gyro_angle[2].push_back(0);
105 
106  gyro_last_it[0].push_back(0);
107  gyro_last_it[1].push_back(0);
108  gyro_last_it[2].push_back(0);
109 
110  angle_last_it[0].push_back(accel_ang_x[i]);
111  angle_last_it[1].push_back(accel_ang_y[i]);
112  angle_last_it[2].push_back(0);
113 
114  angle[0].push_back(0);
115  angle[1].push_back(0);
116  angle[2].push_back(0);
117 
118  }
119 
120  first_run = 1;
121  return;
122  }
123 
124  //getting the gyro's means...
125  if(mean_it<MAX_MEAN_IT)
126  {
127  for(int i= 0;i<sensors_number;i++)
128  {
129  gyro_mean_vect[i][0].push_back(msg->sensors_val[i].S_Gx);
130  gyro_mean_vect[i][1].push_back(msg->sensors_val[i].S_Gy);
131  gyro_mean_vect[i][2].push_back(msg->sensors_val[i].S_Gz);
132  gyro_real_mean[0].push_back(i);
133  gyro_real_mean[1].push_back(i);
134  gyro_real_mean[2].push_back(i);
135  }
136  mean_it++;
137  return;
138  }
139  //getting gyros's means to compensate it (if it's needed!)
140  if(mean_it==MAX_MEAN_IT)
141  {
142  for(int i= 0;i<sensors_number;i++)
143  {
144  for(int j=0;j<mean_it;j++)
145  {
146  gyro_real_mean[0][i]+=gyro_mean_vect[i][0][j];
147  gyro_real_mean[1][i]+=gyro_mean_vect[i][1][j];
148  gyro_real_mean[2][i]+=gyro_mean_vect[i][2][j];
149  }
153  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;
154  }
155  mean_it++;
156  }
157 
158  float sensor_var[sensors_number][9];
159 
160  for(int i = 0; i<sensors_number; i++)
161  {
162  //sensors_values -> variable changing
163  sensor_var[i][0]=msg->sensors_val[i].S_Ax;
164  sensor_var[i][1]=msg->sensors_val[i].S_Ay;
165  sensor_var[i][2]=msg->sensors_val[i].S_Az;
166  sensor_var[i][3]=msg->sensors_val[i].S_Mx;
167  sensor_var[i][4]=msg->sensors_val[i].S_My;
168  sensor_var[i][5]=msg->sensors_val[i].S_Mz;
169  sensor_var[i][6]=msg->sensors_val[i].S_Gx;
170  sensor_var[i][7]=msg->sensors_val[i].S_Gy;
171  sensor_var[i][8]=msg->sensors_val[i].S_Gz;
172 
173  // getting Roll & Pitch from accelerometers
174  ax = sensor_var[i][0];
175  ay = sensor_var[i][1];
176  az = sensor_var[i][2];
177 
178  accel_ang_x[i] = (accel_alpha * atan(ay/sqrt((ax*ax)+(az*az)))) + ((1-accel_alpha) * angle_last_it[0][i]);
179  accel_ang_y[i] = (accel_alpha * atan(ax/sqrt((ay*ay)+(az*az)))) + ((1-accel_alpha) * angle_last_it[1][i]);
180 
181  angle_last_it[0][i]=accel_ang_x[i];
182  angle_last_it[1][i]=accel_ang_y[i];
183 
184  // getting Roll , Pitch & Yaw from gyroscopes
185  gyro_angle[0][i] = ((sensor_var[i][6]-gyro_real_mean[0][i])) * period * GYRO_CONVERT;
186  gyro_angle[1][i] = ((sensor_var[i][7]-gyro_real_mean[1][i])) * period * GYRO_CONVERT;
187  gyro_angle[2][i] = ((sensor_var[i][8]-gyro_real_mean[2][i])) * period * GYRO_CONVERT;
188 
189  float accel_magnitude = sqrt(ax*ax + ay*ay + az*az);
190  angle[0][i] = (1-alpha) * (angle[0][i] + gyro_angle[0][i]) + alpha * accel_ang_x[i];
191  angle[1][i] = (1-alpha) * (angle[1][i] + gyro_angle[1][i]) + alpha * accel_ang_y[i];
192  angle[2][i] = angle[2][i] + gyro_angle[2][i];
193 
194  // setting algorithm results on message variable
195  complementary_filter_network.filtered_imu_network[i].linear_acceleration_x = sensor_var[i][0];
196  complementary_filter_network.filtered_imu_network[i].linear_acceleration_y = sensor_var[i][1];
197  complementary_filter_network.filtered_imu_network[i].linear_acceleration_z = sensor_var[i][2];
198 
199  complementary_filter_network.filtered_imu_network[i].angular_velocity_x = sensor_var[i][6];
200  complementary_filter_network.filtered_imu_network[i].angular_velocity_y = sensor_var[i][7];
201  complementary_filter_network.filtered_imu_network[i].angular_velocity_z = sensor_var[i][8];
202 
203  complementary_filter_network.filtered_imu_network[i].angular_displacement_x = angle[0][i];
204  complementary_filter_network.filtered_imu_network[i].angular_displacement_y = angle[1][i];
205  complementary_filter_network.filtered_imu_network[i].angular_displacement_z = angle[2][i];
206 
207  complementary_filter_network.filtered_imu_network[i].magnetometer_x = sensor_var[i][3];
208  complementary_filter_network.filtered_imu_network[i].magnetometer_y = sensor_var[i][4];
209  complementary_filter_network.filtered_imu_network[i].magnetometer_z = sensor_var[i][5];
210 
211  complementary_filter_network.filtered_imu_network[i].number = i;
212  complementary_filter_network.filtered_imu_network[i].total_number= sensors_number;
213 
214  complementary_filter_network.filtered_imu_network[i].algorithm = 1;
215 
216  complementary_filter_network.filtered_imu_network[i].header.stamp = msg->sensors_val[i].header.stamp;
217  complementary_filter_network.filtered_imu_network[i].header.frame_id = "filtered_imu_network";
218 
219  }
221 
222 }
223 
228 int main(int argc, char **argv)
229 {
230  ros::init(argc, argv, "complementary_imu");
231  n = new(ros::NodeHandle);
232  ros::Subscriber sub = n->subscribe("topic_raw_data", 1000, chatterCallback);
233  chatter_pub = n->advertise<imu_network::filtered_imu_network>("topic_filtered_imu", 1000);
234 
235  ros::spin();
236 
237  return 0;
238 }
vector< float > gyro_angle[3]
vector< float > accel_ang_y
#define GYRO_CONVERT
float period
#define MAX_MEAN_IT
vector< float > angle_last_it[3]
float accel_alpha
int first_run
ros::Publisher chatter_pub
void chatterCallback(const imu_network::sensors_network::ConstPtr &msg)
float alpha
vector< float > gyro_mean_vect[MAX_MEAN_IT][3]
imu_network::filtered_imu_network complementary_filter_network
vector< float > gyro_last_it[3]
int mean_it
vector< float > angle[3]
int sensors_number
vector< float > accel_ang_x
ros::NodeHandle * n
vector< float > gyro_real_mean[3]
int main(int argc, char **argv)


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