diff --git a/matlab/GPSaidedINS.m b/matlab/GPSaidedINS.m
index 13ed46e8f10d8cd038ab8e0ba0aa3b29ce716bc6..2922079b6e992d1c165d68882ecb5a390b42f1da 100644
--- a/matlab/GPSaidedINS.m
+++ b/matlab/GPSaidedINS.m
@@ -163,7 +163,7 @@ for k=2:N
     out_data.x_h(:,k)=x_h;
     out_data.diag_P(:,k)=diag(P);
     out_data.delta_u_h(:,k)=delta_u_h;
-    
+    out_data.sv(k)=sv;
 end
 
 %% plot feedback over P matrix
@@ -297,19 +297,27 @@ R=(eye(3)-OMEGA)*R;
 q=dcm2q(R);
 end
 
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
+%%     Random evolution of visible satellites   %%
+%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
 function sv=random_satellites(sv_old)
 coin=random('uniform',0,1);
 sv=sv_old;
+if sv_old==6  %simulate satellite loss of visibility
+    if coin<0.005
+        sv=5;
+    end
+end
 if sv_old==5  %simulate satellite loss of visibility
-    if coin>0.95
+    if coin>0.99
         sv=6;
     end
-    if coin<0.1
+    if coin<0.001
         sv=4;
     end     
 end
 if sv_old==4  %simulate satellite loss of visibility
-    if coin>0.9
+    if coin>0.99
         sv=5;
     end
     if coin<0.0005
@@ -317,13 +325,8 @@ if sv_old==4  %simulate satellite loss of visibility
     end     
 end
 if sv_old==3  %simulate satellite loss of visibility
-    if coin>0.5
+    if coin>0.95
         sv=4;
     end
 end
-if sv_old==6  %simulate satellite loss of visibility
-    if coin<0.2
-        sv=5;
-    end
-end
 end
diff --git a/matlab/cycling_data.mat b/matlab/cycling_data.mat
new file mode 100644
index 0000000000000000000000000000000000000000..139b5c4b02acab4bc3b5e4f81ecec798dc0e41c6
Binary files /dev/null and b/matlab/cycling_data.mat differ
diff --git a/matlab/main.m b/matlab/main.m
index 1308da4dea72e45e08e222a270f731917ad86f05..7c0d119751251766a1c7444d6c6d55446fb92217 100644
--- a/matlab/main.m
+++ b/matlab/main.m
@@ -10,6 +10,7 @@ load('GNSSaidedINS_data.mat');
 %% Load filter settings
 disp('Loads settings')
 settings=get_settings();
+settings.P_treshold=0.1;
 
 %% Run the GNSS-aided INS
 disp('Runs the GNSS-aided INS')
@@ -17,5 +18,5 @@ out_data=GPSaidedINS(in_data,settings);
 
 %% Plot the data 
 disp('Plot data')
-plot_data(in_data,out_data,'True');drawnow
+%plot_data(in_data,out_data,'True');drawnow
 
diff --git a/matlab/manipulate_cycling_data.m b/matlab/manipulate_cycling_data.m
new file mode 100644
index 0000000000000000000000000000000000000000..884c8c892d76683f57db8e24cae64ad6eb2be9c7
--- /dev/null
+++ b/matlab/manipulate_cycling_data.m
@@ -0,0 +1,38 @@
+
+%load('cycling_data')
+
+% %trying to figure out the unit of measure of the time stamps
+% %total_time=time_stamps(length(time_stamps))-time_stamps(1) ;
+% %real_total_time=(6*60+15)*60;  %about 6 hours and 15 min expressed in seconds
+% %time_unit=real_total_time/total_time
+
+time_stamps=(time_stamps-time_stamps(1))/1.0;
+
+acc=[0,0,0,0];
+gyr=[0,0,0,0];
+gps=[0,0,0,0];
+
+for k=1:length(time_stamps)
+
+    if strcmp(sensor(k),'ACC')
+        acc=[acc;
+             time_stamps(k),a(k),b(k),c(k)];
+    end
+    
+    if strcmp(sensor(k),'GYR')
+        gyr=[gyr;
+             time_stamps(k),a(k),b(k),c(k)];
+    end
+
+    if strcmp(sensor(k),'GPS')
+        gps=[gps;
+             time_stamps(k),a(k),b(k),c(k)];
+    end
+    
+end
+
+acc=acc(2:length(acc),:);
+gyr=gyr(2:length(gyr),:);
+gps=gps(2:length(gps),:);
+
+sum(acc(:,1)-gyr(:,1))
\ No newline at end of file
diff --git a/matlab/plot_data.m b/matlab/plot_data.m
index 28e01120b517e093336615688038e8eb0bce1117..87e49f89deb68b05100738a9dad5331006863727 100644
--- a/matlab/plot_data.m
+++ b/matlab/plot_data.m
@@ -145,5 +145,9 @@ figure(9)
 plot(out_data.P_store)
 title('P controlled')
 
+figure(10)
+plot(out_data.sv)
+title('visible stellites')
+
 end
 
diff --git a/matlab/read_data_from_app.m b/matlab/read_data_from_app.m
new file mode 100644
index 0000000000000000000000000000000000000000..9d462afb78f17b1a538f3673600e76919ea6d119
--- /dev/null
+++ b/matlab/read_data_from_app.m
@@ -0,0 +1,47 @@
+close all
+clear all
+
+% import data from sensor fusion app and translate them in some matlab
+% format
+
+datafile = fopen('sensorLog_20180925T113201.csv');
+%read data from datalog
+temp = textscan(datafile,'%d %s %f %f %f');
+
+
+time = cell2mat(temp(1)); 
+sens = temp{2};
+data = cell2mat(temp(3:5));
+
+fclose(datafile);
+
+%inizializzazioni varie
+h=1;
+j=1;
+time_acc=0;
+time_gps=0;
+acc=rand(1,3);
+gps=[0.0,0.0,0.0,0.0];
+
+
+%cycle over the data
+%for k=1:length(time)
+for k=1:300
+    
+    % if the datum comes from the accelerometer
+    if strcmp(sens(k),'ACC')
+        time_acc=[time_acc;time(k)];
+        acc=[ acc                                      ;
+              [data(k,1),data(k,2),data(k,3)] ];
+        h = h+1;
+    end
+    
+    % if the datum comes from the gps
+    if strcmp(sens(k),'GPS')
+        time_gps=[time_gps;time(k)];
+        gps=[ gps                                      ;
+              [data(k,1),data(k,2),data(k,3)] ];
+        j = j+1;
+    end
+end
+
diff --git a/matlab/run_many.m b/matlab/run_many.m
index b20d4c32de38ae2ba4512d00a36edf375adbdb1a..5f3b55509744c2509506cd4c0ac783a9931f5170 100644
--- a/matlab/run_many.m
+++ b/matlab/run_many.m
@@ -10,24 +10,27 @@ settings=get_settings();
 
 
 settings.P_treshold=0.1;
-%run first simulation
-out_data=GPSaidedINS(in_data,settings);
-energy=out_data.energy;
-error=out_data.error;
+% %run first simulation
+% out_data=GPSaidedINS(in_data,settings);
+% energy=out_data.energy;
+% error=out_data.error;
 
 
+figure(4)
+hold on
+color=[[0.7,0.0,0.0];[0.0,0.7,0.0];[0.7,0.0,0.7];[0.0,0.0,0.7]];
 j=1;
-for P_treshold=[3,6]%[2.3,2.8,3.3,3.8,4.3,4.8,5.3,5.8,6.3,6.8,7.3]
-    %clear energy error
+for P_treshold=[2.0,4.0,6.0,8.0]%[2.3,2.8,3.3,3.8,4.3,4.8,5.3,5.8,6.3,6.8,7.3]
+    clear energy error
     settings.P_treshold=P_treshold;
-%     %run first simulation
-%     out_data=GPSaidedINS(in_data,settings);
-%     %energy=out_data.energy;
-%     %error=out_data.error;
+    %run first simulation
+    out_data=GPSaidedINS(in_data,settings);
+    energy=out_data.energy;
+    error=out_data.error;
 %     energy=[energy,out_data.energy];
 %     error=[error,out_data.error];
     %run more simulations
-    for k=1:20
+    for k=1:10
         %% Run the GNSS-aided INS
         disp('Running the GNSS-aided INS')
         P_treshold
@@ -36,18 +39,17 @@ for P_treshold=[3,6]%[2.3,2.8,3.3,3.8,4.3,4.8,5.3,5.8,6.3,6.8,7.3]
         energy=[energy,out_data.energy];
         error=[error,out_data.error];
     end
-%     %plot data
-%     figure(j)
-%     scatter(energy, error)
-%     xlabel('energy')
-%     ylabel('error')
-%     title(['P treshold = ', num2str(P_treshold)])
-%     grid
-%     j=j+1;
+    %plot data
+    scatter(energy, error,40,color(j,:),'o','filled')
+    xlabel('energy')
+    ylabel('error')
+    %title(['P treshold = ', num2str(P_treshold)])
+    grid
+    j=j+1;
 end
-%plot data
-figure(2)
-scatter(energy, error)
-xlabel('energy')
-ylabel('error')
-grid
+% %plot data
+% figure(2)
+% scatter(energy, error)
+% xlabel('energy')
+% ylabel('error')
+% grid