From e74a82a1a2cb9821e06edbec79e1afb7f11fbbaf Mon Sep 17 00:00:00 2001 From: Claudio <claudio.mandrioli@control.lth.se> Date: Tue, 26 Feb 2019 16:56:48 +0100 Subject: [PATCH] removed comments with unused code --- matlab/GPSaidedINS_car.m | 4 ++-- matlab/GPSaidedINS_cycling.m | 8 ++++---- matlab/gps_randomized_car.m | 3 +-- matlab/gps_randomized_cycling.m | 7 +++---- matlab/main_car.m | 7 +++---- matlab/main_cycling.m | 5 +---- 6 files changed, 14 insertions(+), 20 deletions(-) diff --git a/matlab/GPSaidedINS_car.m b/matlab/GPSaidedINS_car.m index 9c6cdec..3a6f10d 100644 --- a/matlab/GPSaidedINS_car.m +++ b/matlab/GPSaidedINS_car.m @@ -26,6 +26,7 @@ % % Edit: Isaac Skog (skog@kth.se), 2016-09-06 % Revised: Bo Bernhardsson, 2018-01-01 +% Revised: Claudio Mandrioli 2018-02-26 % %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% function out_data=GPSaidedINS_car(in_data,settings) @@ -45,7 +46,6 @@ delta_u_h=zeros(6,1); % Initialize the Kalman filter [P,Q1,Q2,~,~]=init_filter(settings); - % Allocate memory for the output data N=size(u,2); out_data.x_h=zeros(10,N); @@ -96,7 +96,7 @@ for k=2:N end %update sensor state % pre_state=sensor.state; - sensor=gps_randomized(t(k),sensor,turn,sv); %remove _randomized for worst case + sensor=gps_randomized_car(t(k),sensor,turn,sv); %remove _randomized for worst case %determine if GPS position is available GPS_position=strcmp(sensor.state,'position_available'); %compute power consumption diff --git a/matlab/GPSaidedINS_cycling.m b/matlab/GPSaidedINS_cycling.m index c1bed45..e0e9202 100644 --- a/matlab/GPSaidedINS_cycling.m +++ b/matlab/GPSaidedINS_cycling.m @@ -26,6 +26,7 @@ % % Edit: Isaac Skog (skog@kth.se), 2016-09-06 % Revised: Bo Bernhardsson, 2018-01-01 +% Revised: Claudio Mandrioli 2018-02-26 % %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% function out_data=GPSaidedINS(in_data,settings) @@ -81,7 +82,6 @@ pre_state='startup'; %initialize previous state of the sensor (used for display P_store=0; %store summed valued of the trace of P in time sv_store=sv; %store number of visible satellites in time -%for k=2:N for k=start_sim:start_sim+length_sim % Sampling period @@ -91,8 +91,8 @@ for k=start_sim:start_sim+length_sim %% GPS sensor %% %%%%%%%%%%%%%%%%% %randomized number of visible satellites - %sv = random_satellites(sv); - sv=5; + sv = random_satellites(sv); + %sv=5; %control action P_store=[P_store,sum(sqrt(out_data.diag_P(1:3,k-1)))]; if sum(sqrt(out_data.diag_P(1:3,k-1)))<P_treshold @@ -102,7 +102,7 @@ for k=start_sim:start_sim+length_sim end %update sensor state % pre_state=sensor.state; - sensor=gps_randomized(t(k),sensor,turn,sv); %remove _randomized for worst case + sensor=gps_randomized_cycling(t(k),sensor,turn,sv); %remove _randomized for worst case %determine if GPS position is available GPS_position=strcmp(sensor.state,'position_available'); %compute power consumption diff --git a/matlab/gps_randomized_car.m b/matlab/gps_randomized_car.m index fa710c9..95761d0 100644 --- a/matlab/gps_randomized_car.m +++ b/matlab/gps_randomized_car.m @@ -22,7 +22,7 @@ %% %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% -function sensor=gps_randomized(time,sensor_in,turn,sv) +function sensor=gps_randomized_car(time,sensor_in,turn,sv) %% parameters %define how many satellites you need to track given the accuracy requirements @@ -31,7 +31,6 @@ required_sv= 4; ephDuration=1800.0; %bounds for time required for fetching freq and phase fp_lower=0.2; -%fp_upper=500.5; fp_upper=0.8; %% initialize output sensor = sensor_in; diff --git a/matlab/gps_randomized_cycling.m b/matlab/gps_randomized_cycling.m index fa710c9..26f878a 100644 --- a/matlab/gps_randomized_cycling.m +++ b/matlab/gps_randomized_cycling.m @@ -2,7 +2,7 @@ %% GPS sensor dynamics %% %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% -%STATE is a struct (called sensor) with the following fields +%STATE is a struct (called sensor in this function) with the following fields % state -[string]the current proceural state: no_info, cold_start, read_ephemeris, % position_available, warm_start_avaialable, warm_start % fetchfp -[double]at what time freq and phase will be fetched (according to the random extraction) @@ -22,7 +22,7 @@ %% %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% -function sensor=gps_randomized(time,sensor_in,turn,sv) +function sensor=gps_randomized_cycling(time,sensor_in,turn,sv) %% parameters %define how many satellites you need to track given the accuracy requirements @@ -31,8 +31,7 @@ required_sv= 4; ephDuration=1800.0; %bounds for time required for fetching freq and phase fp_lower=0.2; -%fp_upper=500.5; -fp_upper=0.8; +fp_upper=500.0; %% initialize output sensor = sensor_in; diff --git a/matlab/main_car.m b/matlab/main_car.m index 6b83dba..646b88f 100644 --- a/matlab/main_car.m +++ b/matlab/main_car.m @@ -1,21 +1,20 @@ %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% % Script for single experiment with car data -% Plots: %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% %% Load data disp('Loads data') -load('GNSSaidedINS_data.mat'); +load('car_input_data.mat'); %% Load filter settings disp('Loads settings') settings=get_settings_car(); -settings.P_treshold=2.5; +settings.P_treshold=4.1; %% Run the GNSS-aided INS disp('Runs the GNSS-aided INS') -out_data=GPSaidedINS(in_data,settings); +out_data=GPSaidedINS_car(in_data,settings); %% Plot the data disp('Plot data') diff --git a/matlab/main_cycling.m b/matlab/main_cycling.m index 57e3b95..c3cffa9 100644 --- a/matlab/main_cycling.m +++ b/matlab/main_cycling.m @@ -1,17 +1,14 @@ %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% -% Script for single experiment with cycling data -% Plots: +% Script for single experiment with cycling data %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% %% Load data disp('Loads data') -%load('GNSSaidedINS_data.mat'); load('cycling_input_data'); %% Load filter settings disp('Loads settings') -%settings=get_settings(); settings=get_settings_cycling(); settings.P_treshold=2.5; -- GitLab