Fixed GPS Kitti example, VO works but bad results
parent
7a027be7e5
commit
a518dae06a
|
@ -1,237 +0,0 @@
|
||||||
%close all
|
|
||||||
%clc
|
|
||||||
|
|
||||||
import gtsam.*;
|
|
||||||
|
|
||||||
%% Read metadata and compute relative sensor pose transforms
|
|
||||||
IMU_metadata = importdata('KittiEquivBiasedImu_metadata.txt');
|
|
||||||
IMU_metadata = cell2struct(num2cell(IMU_metadata.data), IMU_metadata.colheaders, 2);
|
|
||||||
IMUinBody = Pose3.Expmap([IMU_metadata.BodyPtx; IMU_metadata.BodyPty; IMU_metadata.BodyPtz;
|
|
||||||
IMU_metadata.BodyPrx; IMU_metadata.BodyPry; IMU_metadata.BodyPrz; ]);
|
|
||||||
if ~IMUinBody.equals(Pose3, 1e-5)
|
|
||||||
error 'Currently only support IMUinBody is identity, i.e. IMU and body frame are the same';
|
|
||||||
end
|
|
||||||
|
|
||||||
VO_metadata = importdata('KittiRelativePose_metadata.txt');
|
|
||||||
VO_metadata = cell2struct(num2cell(VO_metadata.data), VO_metadata.colheaders, 2);
|
|
||||||
VOinBody = Pose3.Expmap([VO_metadata.BodyPtx; VO_metadata.BodyPty; VO_metadata.BodyPtz;
|
|
||||||
VO_metadata.BodyPrx; VO_metadata.BodyPry; VO_metadata.BodyPrz; ]);
|
|
||||||
|
|
||||||
GPS_metadata = importdata('KittiGps_metadata.txt');
|
|
||||||
GPS_metadata = cell2struct(num2cell(GPS_metadata.data), GPS_metadata.colheaders, 2);
|
|
||||||
GPSinBody = Pose3.Expmap([GPS_metadata.BodyPtx; GPS_metadata.BodyPty; GPS_metadata.BodyPtz;
|
|
||||||
GPS_metadata.BodyPrx; GPS_metadata.BodyPry; GPS_metadata.BodyPrz; ]);
|
|
||||||
|
|
||||||
VOinIMU = IMUinBody.inverse().compose(VOinBody);
|
|
||||||
GPSinIMU = IMUinBody.inverse().compose(GPSinBody);
|
|
||||||
|
|
||||||
%% Read data and change coordinate frame of GPS and VO measurements to IMU frame
|
|
||||||
IMU_data = importdata('KittiEquivBiasedImu.txt');
|
|
||||||
IMU_data = cell2struct(num2cell(IMU_data.data), IMU_data.colheaders, 2);
|
|
||||||
imum = cellfun(@(x) x', num2cell([ [IMU_data.accelX]' [IMU_data.accelY]' [IMU_data.accelZ]' [IMU_data.omegaX]' [IMU_data.omegaY]' [IMU_data.omegaZ]' ], 2), 'UniformOutput', false);
|
|
||||||
[IMU_data.acc_omega] = deal(imum{:});
|
|
||||||
IMU_data = rmfield(IMU_data, { 'accelX' 'accelY' 'accelZ' 'omegaX' 'omegaY' 'omegaZ' });
|
|
||||||
clear imum
|
|
||||||
|
|
||||||
VO_data = importdata('KittiRelativePose.txt');
|
|
||||||
VO_data = cell2struct(num2cell(VO_data.data), VO_data.colheaders, 2);
|
|
||||||
% Merge relative pose fields and convert to Pose3
|
|
||||||
logposes = [ [VO_data.dtx]' [VO_data.dty]' [VO_data.dtz]' [VO_data.drx]' [VO_data.dry]' [VO_data.drz]' ];
|
|
||||||
logposes = num2cell(logposes, 2);
|
|
||||||
relposes = arrayfun(@(x) {gtsam.Pose3.Expmap(x{:}')}, logposes);
|
|
||||||
relposes = arrayfun(@(x) {VOinIMU.compose(x{:}).compose(VOinIMU.inverse())}, relposes);
|
|
||||||
[VO_data.RelativePose] = deal(relposes{:});
|
|
||||||
VO_data = rmfield(VO_data, { 'dtx' 'dty' 'dtz' 'drx' 'dry' 'drz' });
|
|
||||||
clear logposes relposes
|
|
||||||
|
|
||||||
GPS_data = importdata('KittiGps.txt');
|
|
||||||
GPS_data = cell2struct(num2cell(GPS_data.data), GPS_data.colheaders, 2);
|
|
||||||
|
|
||||||
%% Set initial conditions for the estimated trajectory
|
|
||||||
disp('TODO: we have GPS so this initialization is not right')
|
|
||||||
currentPoseGlobal = Pose3; % initial pose is the reference frame (navigation frame)
|
|
||||||
currentVelocityGlobal = [0;0;0]; % the vehicle is stationary at the beginning
|
|
||||||
bias_acc = [0;0;0]; % we initialize accelerometer biases to zero
|
|
||||||
bias_omega = [0;0;0]; % we initialize gyro biases to zero
|
|
||||||
|
|
||||||
%% Solver object
|
|
||||||
isamParams = ISAM2Params;
|
|
||||||
isamParams.setRelinearizeSkip(1);
|
|
||||||
isam = gtsam.ISAM2(isamParams);
|
|
||||||
|
|
||||||
%% create nonlinear factor graph
|
|
||||||
factors = NonlinearFactorGraph;
|
|
||||||
values = Values;
|
|
||||||
|
|
||||||
%% Create prior on initial pose, velocity, and biases
|
|
||||||
sigma_init_x = 1.0;
|
|
||||||
sigma_init_v = 1.0;
|
|
||||||
sigma_init_b = 1.0;
|
|
||||||
|
|
||||||
values.insert(symbol('x',0), currentPoseGlobal);
|
|
||||||
values.insert(symbol('v',0), LieVector(currentVelocityGlobal) );
|
|
||||||
values.insert(symbol('b',0), imuBias.ConstantBias(bias_acc,bias_omega) );
|
|
||||||
|
|
||||||
disp('TODO: we have GPS so this initialization is not right')
|
|
||||||
% Prior on initial pose
|
|
||||||
factors.add(PriorFactorPose3(symbol('x',0), ...
|
|
||||||
currentPoseGlobal, noiseModel.Isotropic.Sigma(6, sigma_init_x)));
|
|
||||||
% Prior on initial velocity
|
|
||||||
factors.add(PriorFactorLieVector(symbol('v',0), ...
|
|
||||||
LieVector(currentVelocityGlobal), noiseModel.Isotropic.Sigma(3, sigma_init_v)));
|
|
||||||
% Prior on initial bias
|
|
||||||
factors.add(PriorFactorConstantBias(symbol('b',0), ...
|
|
||||||
imuBias.ConstantBias(bias_acc,bias_omega), noiseModel.Isotropic.Sigma(6, sigma_init_b)));
|
|
||||||
|
|
||||||
currentSummarizedMeasurement = [];
|
|
||||||
|
|
||||||
% Measurement types:
|
|
||||||
% 1: VO
|
|
||||||
% 2: GPS
|
|
||||||
% 3: IMU
|
|
||||||
timestamps = sortrows( [ ...
|
|
||||||
[VO_data.Time]' 1*ones(length([VO_data.Time]), 1); ...
|
|
||||||
%[GPS_data.Time]' 2*ones(length([GPS_data.Time]), 1); ...
|
|
||||||
%[IMU_data.Time]' 3*ones(length([IMU_data.Time]), 1); ...
|
|
||||||
], 1); % this are the time-stamps at which we want to initialize a new node in the graph
|
|
||||||
|
|
||||||
%% Main loop:
|
|
||||||
% (1) we read the measurements
|
|
||||||
% (2) we create the corresponding factors in the graph
|
|
||||||
% (3) we solve the graph to obtain and optimal estimate of robot trajectory
|
|
||||||
|
|
||||||
% t_previous = 0;%LC
|
|
||||||
% poseIndex = 0;%LC
|
|
||||||
|
|
||||||
% currentPose = Pose3; %LC
|
|
||||||
|
|
||||||
position= []; %LC
|
|
||||||
|
|
||||||
for measurementIndex = 1:size(timestamps,1)
|
|
||||||
|
|
||||||
measurementIndex
|
|
||||||
|
|
||||||
% currentPose = currentPose.compose(VO_data(measurementIndex).RelativePose);%LC
|
|
||||||
%
|
|
||||||
% position(measurementIndex,:) = currentPose.translation.vector;%LC
|
|
||||||
|
|
||||||
|
|
||||||
% At each non=IMU measurement we initialize a new node in the graph
|
|
||||||
currentPoseKey = symbol('x',poseIndex);
|
|
||||||
currentVelKey = symbol('v',poseIndex);
|
|
||||||
currentBiasKey = symbol('b',poseIndex);
|
|
||||||
|
|
||||||
t = timestamps(measurementIndex, 1);
|
|
||||||
type = timestamps(measurementIndex, 2);
|
|
||||||
|
|
||||||
% if type == 3
|
|
||||||
% % Integrate IMU
|
|
||||||
%
|
|
||||||
% if isempty(currentSummarizedMeasurement)
|
|
||||||
% % Create initial empty summarized measurement
|
|
||||||
% % we assume that each row of the IMU.txt file has the following structure:
|
|
||||||
% % timestamp delta_t acc_x acc_y acc_z omega_x omega_y omega_z
|
|
||||||
% currentBias = isam.calculateEstimate(currentBiasKey - 1);
|
|
||||||
% currentSummarizedMeasurement = gtsam.ImuFactorPreintegratedMeasurements( ...
|
|
||||||
% currentBias, IMU_metadata.AccelerometerSigma.^2 * eye(3), ...
|
|
||||||
% IMU_metadata.GyroscopeSigma.^2 * eye(3), IMU_metadata.IntegrationSigma.^2 * eye(3));
|
|
||||||
% end
|
|
||||||
%
|
|
||||||
% % Accumulate preintegrated measurement
|
|
||||||
% deltaT = IMU_data(index).dt;
|
|
||||||
% accMeas = IMU_data(index).acc_omega(1:3);
|
|
||||||
% omegaMeas = IMU_data(index).acc_omega(4:6);
|
|
||||||
% currentSummarizedMeasurement.integrateMeasurement(accMeas, omegaMeas, deltaT);
|
|
||||||
%
|
|
||||||
% else
|
|
||||||
% % Create IMU factor
|
|
||||||
% factors.add(ImuFactor( ...
|
|
||||||
% currentPoseKey-1, currentVelKey-1, ...
|
|
||||||
% currentPoseKey, currentVelKey, ...
|
|
||||||
% currentBiasKey-1, currentSummarizedMeasurement, g, cor_v, ...
|
|
||||||
% currentSummarizedMeasurement.PreintMeasCov));
|
|
||||||
%
|
|
||||||
% % Reset summarized measurement
|
|
||||||
% currentSummarizedMeasurement = [];
|
|
||||||
%
|
|
||||||
% if type == 1
|
|
||||||
% % Create VO factor
|
|
||||||
% elseif type == 2
|
|
||||||
% % Create GPS factor
|
|
||||||
% end
|
|
||||||
%
|
|
||||||
% poseIndex = poseIndex + 1;
|
|
||||||
% end
|
|
||||||
|
|
||||||
|
|
||||||
% =======================================================================
|
|
||||||
|
|
||||||
|
|
||||||
%% add factor corresponding to GPS measurements (if available at the current time)
|
|
||||||
% % =======================================================================
|
|
||||||
% if isempty( find(GPS_data(:,1) == t ) ) == 0 % it is a GPS measurement
|
|
||||||
% if length( find(GPS_data(:,1)) ) > 1
|
|
||||||
% error('more GPS measurements at the same time stamp: it should be an error')
|
|
||||||
% end
|
|
||||||
%
|
|
||||||
% index = find(GPS_data(:,1) == t ); % the row of the IMU_data matrix that we have to integrate
|
|
||||||
% GPSmeas = GPS_data(index,2:4);
|
|
||||||
%
|
|
||||||
% noiseModelGPS = ???; % noiseModelGPS.Isotropic.Sigma(6, sigma_init_x))
|
|
||||||
%
|
|
||||||
% % add factor
|
|
||||||
% disp('TODO: is the GPS noise right?')
|
|
||||||
% factors.add(PriorFactor???(currentPoseKey, GPSmeas, noiseModelGPS) );
|
|
||||||
% end
|
|
||||||
% =======================================================================
|
|
||||||
|
|
||||||
|
|
||||||
% %% add factor corresponding to VO measurements (if available at the current time)
|
|
||||||
% % =======================================================================
|
|
||||||
% if isempty( find([VO_data.Time] == t, 1) )== 0 % it is a GPS measurement
|
|
||||||
% if length( find([VO_data.Time] == t) ) > 1
|
|
||||||
% error('more VO measurements at the same time stamp: it should be an error')
|
|
||||||
% end
|
|
||||||
%
|
|
||||||
% index = find([VO_data.Time] == t, 1); % the row of the IMU_data matrix that we have to integrate
|
|
||||||
%
|
|
||||||
% VOpose = VO_data(index).RelativePose;
|
|
||||||
% noiseModelVO = noiseModel.Diagonal.Sigmas([ IMU_metadata.RotationSigma * [1;1;1]; IMU_metadata.TranslationSigma * [1;1;1] ]);
|
|
||||||
%
|
|
||||||
% % add factor
|
|
||||||
% disp('TODO: is the VO noise right?')
|
|
||||||
% factors.add(BetweenFactorPose3(lastVOPoseKey, currentPoseKey, VOpose, noiseModelVO));
|
|
||||||
%
|
|
||||||
% lastVOPoseKey = currentPoseKey;
|
|
||||||
% end
|
|
||||||
% % =======================================================================
|
|
||||||
%
|
|
||||||
% disp('TODO: add values')
|
|
||||||
% % values.insert(, initialPose);
|
|
||||||
% % values.insert(symbol('v',lastIndex+1), initialVel);
|
|
||||||
%
|
|
||||||
% %% Update solver
|
|
||||||
% % =======================================================================
|
|
||||||
% isam.update(factors, values);
|
|
||||||
% factors = NonlinearFactorGraph;
|
|
||||||
% values = Values;
|
|
||||||
%
|
|
||||||
% isam.calculateEstimate(currentPoseKey);
|
|
||||||
% % M = isam.marginalCovariance(key_pose);
|
|
||||||
% % =======================================================================
|
|
||||||
%
|
|
||||||
% previousPoseKey = currentPoseKey;
|
|
||||||
% previousVelKey = currentVelKey;
|
|
||||||
% t_previous = t;
|
|
||||||
end
|
|
||||||
|
|
||||||
figure
|
|
||||||
plot(position(:,1),position(:,2))
|
|
||||||
|
|
||||||
|
|
||||||
% figure(1)
|
|
||||||
% hold on;
|
|
||||||
% plot(positions(1,:), positions(2,:), '-b');
|
|
||||||
% plot3DTrajectory(isam.calculateEstimate, 'g-');
|
|
||||||
% axis equal;
|
|
||||||
% legend('true trajectory', 'traj integrated in body', 'traj integrated in nav')
|
|
|
@ -0,0 +1,191 @@
|
||||||
|
close all
|
||||||
|
clc
|
||||||
|
|
||||||
|
import gtsam.*;
|
||||||
|
disp('Example of application of ISAM2 for visual-inertial navigation on the KITTI VISION BENCHMARK SUITE (http://www.computervisiononline.com/dataset/kitti-vision-benchmark-suite)')
|
||||||
|
|
||||||
|
%% Read metadata and compute relative sensor pose transforms
|
||||||
|
% IMU metadata
|
||||||
|
disp('-- Reading sensor metadata')
|
||||||
|
IMU_metadata = importdata('KittiEquivBiasedImu_metadata.txt');
|
||||||
|
IMU_metadata = cell2struct(num2cell(IMU_metadata.data), IMU_metadata.colheaders, 2);
|
||||||
|
IMUinBody = Pose3.Expmap([IMU_metadata.BodyPtx; IMU_metadata.BodyPty; IMU_metadata.BodyPtz;
|
||||||
|
IMU_metadata.BodyPrx; IMU_metadata.BodyPry; IMU_metadata.BodyPrz; ]);
|
||||||
|
if ~IMUinBody.equals(Pose3, 1e-5)
|
||||||
|
error 'Currently only support IMUinBody is identity, i.e. IMU and body frame are the same';
|
||||||
|
end
|
||||||
|
|
||||||
|
% VO metadata
|
||||||
|
VO_metadata = importdata('KittiRelativePose_metadata.txt');
|
||||||
|
VO_metadata = cell2struct(num2cell(VO_metadata.data), VO_metadata.colheaders, 2);
|
||||||
|
VOinBody = Pose3.Expmap([VO_metadata.BodyPtx; VO_metadata.BodyPty; VO_metadata.BodyPtz;
|
||||||
|
VO_metadata.BodyPrx; VO_metadata.BodyPry; VO_metadata.BodyPrz; ]);
|
||||||
|
VOinIMU = IMUinBody.inverse().compose(VOinBody);
|
||||||
|
|
||||||
|
% GPS metadata
|
||||||
|
GPS_metadata = importdata('KittiGps_metadata.txt');
|
||||||
|
GPS_metadata = cell2struct(num2cell(GPS_metadata.data), GPS_metadata.colheaders, 2);
|
||||||
|
GPSinBody = Pose3.Expmap([GPS_metadata.BodyPtx; GPS_metadata.BodyPty; GPS_metadata.BodyPtz;
|
||||||
|
GPS_metadata.BodyPrx; GPS_metadata.BodyPry; GPS_metadata.BodyPrz; ]);
|
||||||
|
GPSinIMU = IMUinBody.inverse().compose(GPSinBody);
|
||||||
|
|
||||||
|
%% Read data and change coordinate frame of GPS and VO measurements to IMU frame
|
||||||
|
disp('-- Reading sensor data from file')
|
||||||
|
% IMU data
|
||||||
|
IMU_data = importdata('KittiEquivBiasedImu.txt');
|
||||||
|
IMU_data = cell2struct(num2cell(IMU_data.data), IMU_data.colheaders, 2);
|
||||||
|
imum = cellfun(@(x) x', num2cell([ [IMU_data.accelX]' [IMU_data.accelY]' [IMU_data.accelZ]' [IMU_data.omegaX]' [IMU_data.omegaY]' [IMU_data.omegaZ]' ], 2), 'UniformOutput', false);
|
||||||
|
[IMU_data.acc_omega] = deal(imum{:});
|
||||||
|
%IMU_data = rmfield(IMU_data, { 'accelX' 'accelY' 'accelZ' 'omegaX' 'omegaY' 'omegaZ' });
|
||||||
|
clear imum
|
||||||
|
|
||||||
|
% VO data
|
||||||
|
VO_data = importdata('KittiRelativePose.txt');
|
||||||
|
VO_data = cell2struct(num2cell(VO_data.data), VO_data.colheaders, 2);
|
||||||
|
% Merge relative pose fields and convert to Pose3
|
||||||
|
logposes = [ [VO_data.dtx]' [VO_data.dty]' [VO_data.dtz]' [VO_data.drx]' [VO_data.dry]' [VO_data.drz]' ];
|
||||||
|
logposes = num2cell(logposes, 2);
|
||||||
|
relposes = arrayfun(@(x) {gtsam.Pose3.Expmap(x{:}')}, logposes);
|
||||||
|
relposes = arrayfun(@(x) {VOinIMU.compose(x{:}).compose(VOinIMU.inverse())}, relposes);
|
||||||
|
[VO_data.RelativePose] = deal(relposes{:});
|
||||||
|
VO_data = rmfield(VO_data, { 'dtx' 'dty' 'dtz' 'drx' 'dry' 'drz' });
|
||||||
|
noiseModelVO = noiseModel.Diagonal.Sigmas([ VO_metadata.RotationSigma * [1;1;1]; VO_metadata.TranslationSigma * [1;1;1] ]);
|
||||||
|
clear logposes relposes
|
||||||
|
|
||||||
|
% % % GPS data
|
||||||
|
% % GPS_data = importdata('KittiGps.txt');
|
||||||
|
% % GPS_data = cell2struct(num2cell(GPS_data.data), GPS_data.colheaders, 2);
|
||||||
|
% % % Convert GPS from lat/long to meters
|
||||||
|
% % [ x, y, ~ ] = deg2utm( [GPS_data.Latitude], [GPS_data.Longitude] );
|
||||||
|
% % for i = 1:numel(x)
|
||||||
|
% % GPS_data(i).Position = gtsam.Point3(x(i), y(i), GPS_data(i).Altitude);
|
||||||
|
% % end
|
||||||
|
% % % % Calculate GPS sigma in meters
|
||||||
|
% % % [ xSig, ySig, ~ ] = deg2utm( [GPS_data.Latitude] + [GPS_data.PositionSigma], ...
|
||||||
|
% % % [GPS_data.Longitude] + [GPS_data.PositionSigma]);
|
||||||
|
% % % xSig = xSig - x;
|
||||||
|
% % % ySig = ySig - y;
|
||||||
|
% % %% Start at time of first GPS measurement
|
||||||
|
% % % firstGPSPose = 1;
|
||||||
|
|
||||||
|
%% Get initial conditions for the estimated trajectory
|
||||||
|
% % % currentPoseGlobal = Pose3(Rot3, GPS_data(firstGPSPose).Position); % initial pose is the reference frame (navigation frame)
|
||||||
|
currentPoseGlobal = Pose3;
|
||||||
|
currentVelocityGlobal = LieVector([0;0;0]); % the vehicle is stationary at the beginning
|
||||||
|
currentBias = imuBias.ConstantBias(zeros(3,1), zeros(3,1));
|
||||||
|
sigma_init_x = noiseModel.Isotropic.Sigma(6, 0.01);
|
||||||
|
sigma_init_v = noiseModel.Isotropic.Sigma(3, 1000.0);
|
||||||
|
sigma_init_b = noiseModel.Isotropic.Sigma(6, 0.01);
|
||||||
|
g = [0;0;-9.8];
|
||||||
|
w_coriolis = [0;0;0];
|
||||||
|
|
||||||
|
%% Solver object
|
||||||
|
isamParams = ISAM2Params;
|
||||||
|
isamParams.setFactorization('QR');
|
||||||
|
isamParams.setRelinearizeSkip(1);
|
||||||
|
isam = gtsam.ISAM2(isamParams);
|
||||||
|
newFactors = NonlinearFactorGraph;
|
||||||
|
newValues = Values;
|
||||||
|
|
||||||
|
%% Main loop:
|
||||||
|
% (1) we read the measurements
|
||||||
|
% (2) we create the corresponding factors in the graph
|
||||||
|
% (3) we solve the graph to obtain and optimal estimate of robot trajectory
|
||||||
|
timestamps = sortrows( [ ...
|
||||||
|
[VO_data.Time]' 1*ones(length([VO_data.Time]), 1); ...
|
||||||
|
% % %[GPS_data.Time]' 2*ones(length([GPS_data.Time]), 1); ...
|
||||||
|
], 1); % this are the time-stamps at which we want to initialize a new node in the graph
|
||||||
|
|
||||||
|
timestamps = timestamps(15:end,:); % there seem to be issues with the initial IMU measurements
|
||||||
|
IMUtimes = [IMU_data.Time];
|
||||||
|
VOPoseKeys = []; % here we store the keys of the poses involved in VO (between) factors
|
||||||
|
|
||||||
|
for measurementIndex = 1:length(timestamps)
|
||||||
|
|
||||||
|
% At each non=IMU measurement we initialize a new node in the graph
|
||||||
|
currentPoseKey = symbol('x',measurementIndex);
|
||||||
|
currentVelKey = symbol('v',measurementIndex);
|
||||||
|
currentBiasKey = symbol('b',measurementIndex);
|
||||||
|
t = timestamps(measurementIndex, 1);
|
||||||
|
type = timestamps(measurementIndex, 2);
|
||||||
|
|
||||||
|
%% bookkeeping
|
||||||
|
if type == 1 % we store the keys corresponding to VO measurements
|
||||||
|
VOPoseKeys = [VOPoseKeys; currentPoseKey];
|
||||||
|
end
|
||||||
|
|
||||||
|
if measurementIndex == 1
|
||||||
|
%% Create initial estimate and prior on initial pose, velocity, and biases
|
||||||
|
newValues.insert(currentPoseKey, currentPoseGlobal);
|
||||||
|
newValues.insert(currentVelKey, currentVelocityGlobal);
|
||||||
|
newValues.insert(currentBiasKey, currentBias);
|
||||||
|
newFactors.add(PriorFactorPose3(currentPoseKey, currentPoseGlobal, sigma_init_x));
|
||||||
|
newFactors.add(PriorFactorLieVector(currentVelKey, currentVelocityGlobal, sigma_init_v));
|
||||||
|
newFactors.add(PriorFactorConstantBias(currentBiasKey, currentBias, sigma_init_b));
|
||||||
|
else
|
||||||
|
t_previous = timestamps(measurementIndex-1, 1);
|
||||||
|
%% Summarize IMU data between the previous GPS measurement and now
|
||||||
|
IMUindices = find(IMUtimes >= t_previous & IMUtimes <= t);
|
||||||
|
|
||||||
|
if ~isempty(IMUindices) % if there are IMU measurements to integrate
|
||||||
|
currentSummarizedMeasurement = gtsam.ImuFactorPreintegratedMeasurements( ...
|
||||||
|
currentBias, IMU_metadata.AccelerometerSigma.^2 * eye(3), ...
|
||||||
|
IMU_metadata.GyroscopeSigma.^2 * eye(3), IMU_metadata.IntegrationSigma.^2 * eye(3));
|
||||||
|
|
||||||
|
for imuIndex = IMUindices
|
||||||
|
accMeas = [ IMU_data(imuIndex).accelX; IMU_data(imuIndex).accelY; IMU_data(imuIndex).accelZ ];
|
||||||
|
omegaMeas = [ IMU_data(imuIndex).omegaX; IMU_data(imuIndex).omegaY; IMU_data(imuIndex).omegaZ ];
|
||||||
|
deltaT = IMU_data(imuIndex).dt;
|
||||||
|
currentSummarizedMeasurement.integrateMeasurement(accMeas, omegaMeas, deltaT);
|
||||||
|
end
|
||||||
|
|
||||||
|
% Create IMU factor
|
||||||
|
newFactors.add(ImuFactor( ...
|
||||||
|
currentPoseKey-1, currentVelKey-1, ...
|
||||||
|
currentPoseKey, currentVelKey, ...
|
||||||
|
currentBiasKey, currentSummarizedMeasurement, g, w_coriolis));
|
||||||
|
|
||||||
|
else % if there are no IMU measurements
|
||||||
|
error('no IMU measurements in [t_previous, t]')
|
||||||
|
end
|
||||||
|
|
||||||
|
% LC: sigma_init_b is wrong: this should be some uncertainty on bias evolution given in the IMU metadata
|
||||||
|
newFactors.add(BetweenFactorConstantBias(currentBiasKey-1, currentBiasKey, imuBias.ConstantBias(zeros(3,1), zeros(3,1)), sigma_init_b));
|
||||||
|
|
||||||
|
%% Create GPS factor
|
||||||
|
if type == 2
|
||||||
|
newFactors.add(PriorFactorPose3(currentPoseKey, Pose3(currentPoseGlobal.rotation, GPS_data(measurementIndex).Position), ...
|
||||||
|
noiseModel.Diagonal.Precisions([ zeros(3,1); 1./(GPS_data(measurementIndex).PositionSigma).^2*ones(3,1) ])));
|
||||||
|
end
|
||||||
|
|
||||||
|
%% Create VO factor
|
||||||
|
if type == 1
|
||||||
|
VOpose = VO_data(measurementIndex).RelativePose;
|
||||||
|
newFactors.add(BetweenFactorPose3(VOPoseKeys(end-1), VOPoseKeys(end), VOpose, noiseModelVO));
|
||||||
|
end
|
||||||
|
|
||||||
|
% Add initial value
|
||||||
|
% newValues.insert(currentPoseKey, Pose3(currentPoseGlobal.rotation, GPS_data(measurementIndex).Position));
|
||||||
|
newValues.insert(currentPoseKey,currentPoseGlobal);
|
||||||
|
newValues.insert(currentVelKey, currentVelocityGlobal);
|
||||||
|
newValues.insert(currentBiasKey, currentBias);
|
||||||
|
|
||||||
|
% Update solver
|
||||||
|
% =======================================================================
|
||||||
|
isam.update(newFactors, newValues);
|
||||||
|
newFactors = NonlinearFactorGraph;
|
||||||
|
newValues = Values;
|
||||||
|
|
||||||
|
if rem(measurementIndex,100)==0 % plot every 100 time steps
|
||||||
|
cla;
|
||||||
|
plot3DTrajectory(isam.calculateEstimate, 'g-');
|
||||||
|
axis equal
|
||||||
|
drawnow;
|
||||||
|
end
|
||||||
|
% =======================================================================
|
||||||
|
currentPoseGlobal = isam.calculateEstimate(currentPoseKey);
|
||||||
|
currentVelocityGlobal = isam.calculateEstimate(currentVelKey);
|
||||||
|
currentBias = isam.calculateEstimate(currentBiasKey);
|
||||||
|
end
|
||||||
|
|
||||||
|
end % end main loop
|
|
@ -0,0 +1,149 @@
|
||||||
|
close all
|
||||||
|
clc
|
||||||
|
|
||||||
|
import gtsam.*;
|
||||||
|
disp('Example of application of ISAM2 for GPS-aided navigation on the KITTI VISION BENCHMARK SUITE (http://www.computervisiononline.com/dataset/kitti-vision-benchmark-suite)')
|
||||||
|
|
||||||
|
%% Read metadata and compute relative sensor pose transforms
|
||||||
|
% IMU metadata
|
||||||
|
disp('-- Reading sensor metadata')
|
||||||
|
IMU_metadata = importdata('KittiEquivBiasedImu_metadata.txt');
|
||||||
|
IMU_metadata = cell2struct(num2cell(IMU_metadata.data), IMU_metadata.colheaders, 2);
|
||||||
|
IMUinBody = Pose3.Expmap([IMU_metadata.BodyPtx; IMU_metadata.BodyPty; IMU_metadata.BodyPtz;
|
||||||
|
IMU_metadata.BodyPrx; IMU_metadata.BodyPry; IMU_metadata.BodyPrz; ]);
|
||||||
|
if ~IMUinBody.equals(Pose3, 1e-5)
|
||||||
|
error 'Currently only support IMUinBody is identity, i.e. IMU and body frame are the same';
|
||||||
|
end
|
||||||
|
|
||||||
|
% GPS metadata
|
||||||
|
GPS_metadata = importdata('KittiRelativePose_metadata.txt');
|
||||||
|
GPS_metadata = cell2struct(num2cell(GPS_metadata.data), GPS_metadata.colheaders, 2);
|
||||||
|
|
||||||
|
%% Read data
|
||||||
|
disp('-- Reading sensor data from file')
|
||||||
|
% IMU data
|
||||||
|
IMU_data = importdata('KittiEquivBiasedImu.txt');
|
||||||
|
IMU_data = cell2struct(num2cell(IMU_data.data), IMU_data.colheaders, 2);
|
||||||
|
imum = cellfun(@(x) x', num2cell([ [IMU_data.accelX]' [IMU_data.accelY]' [IMU_data.accelZ]' [IMU_data.omegaX]' [IMU_data.omegaY]' [IMU_data.omegaZ]' ], 2), 'UniformOutput', false);
|
||||||
|
[IMU_data.acc_omega] = deal(imum{:});
|
||||||
|
clear imum
|
||||||
|
|
||||||
|
% GPS data
|
||||||
|
GPS_data = importdata('Gps_converted.txt');
|
||||||
|
GPS_data = cell2struct(num2cell(GPS_data.data), GPS_data.colheaders, 2);
|
||||||
|
for i = 1:numel(GPS_data)
|
||||||
|
GPS_data(i).Position = gtsam.Point3(GPS_data(i).X, GPS_data(i).Y, GPS_data(i).Z);
|
||||||
|
end
|
||||||
|
noiseModelGPS = noiseModel.Diagonal.Precisions([ [0;0;0]; 1.0/0.07 * [1;1;1] ]);
|
||||||
|
firstGPSPose = 2;
|
||||||
|
GPSskip = 10; % Skip this many GPS measurements each time
|
||||||
|
|
||||||
|
%% Get initial conditions for the estimated trajectory
|
||||||
|
currentPoseGlobal = Pose3(Rot3, GPS_data(firstGPSPose).Position); % initial pose is the reference frame (navigation frame)
|
||||||
|
currentVelocityGlobal = LieVector([0;0;0]); % the vehicle is stationary at the beginning
|
||||||
|
currentBias = imuBias.ConstantBias(zeros(3,1), zeros(3,1));
|
||||||
|
sigma_init_x = noiseModel.Isotropic.Precisions([ 0.0; 0.0; 0.0; 1; 1; 1 ]);
|
||||||
|
sigma_init_v = noiseModel.Isotropic.Sigma(3, 1000.0);
|
||||||
|
sigma_init_b = noiseModel.Isotropic.Sigmas([ 0.100; 0.100; 0.100; 5.00e-05; 5.00e-05; 5.00e-05 ]);
|
||||||
|
sigma_between_b = [ IMU_metadata.AccelerometerBiasSigma * ones(3,1); IMU_metadata.GyroscopeBiasSigma * ones(3,1) ];
|
||||||
|
g = [0;0;-9.8];
|
||||||
|
w_coriolis = [0;0;0];
|
||||||
|
|
||||||
|
%% Solver object
|
||||||
|
isamParams = ISAM2Params;
|
||||||
|
isamParams.setFactorization('CHOLESKY');
|
||||||
|
isamParams.setRelinearizeSkip(10);
|
||||||
|
isam = gtsam.ISAM2(isamParams);
|
||||||
|
newFactors = NonlinearFactorGraph;
|
||||||
|
newValues = Values;
|
||||||
|
|
||||||
|
%% Main loop:
|
||||||
|
% (1) we read the measurements
|
||||||
|
% (2) we create the corresponding factors in the graph
|
||||||
|
% (3) we solve the graph to obtain and optimal estimate of robot trajectory
|
||||||
|
IMUtimes = [IMU_data.Time];
|
||||||
|
|
||||||
|
disp('-- Starting main loop: inference is performed at each time step, but we plot trajectory every 10 steps')
|
||||||
|
|
||||||
|
for measurementIndex = firstGPSPose:length(GPS_data)
|
||||||
|
|
||||||
|
% At each non=IMU measurement we initialize a new node in the graph
|
||||||
|
currentPoseKey = symbol('x',measurementIndex);
|
||||||
|
currentVelKey = symbol('v',measurementIndex);
|
||||||
|
currentBiasKey = symbol('b',measurementIndex);
|
||||||
|
t = GPS_data(measurementIndex, 1).Time;
|
||||||
|
|
||||||
|
if measurementIndex == firstGPSPose
|
||||||
|
%% Create initial estimate and prior on initial pose, velocity, and biases
|
||||||
|
newValues.insert(currentPoseKey, currentPoseGlobal);
|
||||||
|
newValues.insert(currentVelKey, currentVelocityGlobal);
|
||||||
|
newValues.insert(currentBiasKey, currentBias);
|
||||||
|
newFactors.add(PriorFactorPose3(currentPoseKey, currentPoseGlobal, sigma_init_x));
|
||||||
|
newFactors.add(PriorFactorLieVector(currentVelKey, currentVelocityGlobal, sigma_init_v));
|
||||||
|
newFactors.add(PriorFactorConstantBias(currentBiasKey, currentBias, sigma_init_b));
|
||||||
|
else
|
||||||
|
t_previous = GPS_data(measurementIndex-1, 1).Time;
|
||||||
|
%% Summarize IMU data between the previous GPS measurement and now
|
||||||
|
IMUindices = find(IMUtimes >= t_previous & IMUtimes <= t);
|
||||||
|
|
||||||
|
currentSummarizedMeasurement = gtsam.ImuFactorPreintegratedMeasurements( ...
|
||||||
|
currentBias, IMU_metadata.AccelerometerSigma.^2 * eye(3), ...
|
||||||
|
IMU_metadata.GyroscopeSigma.^2 * eye(3), IMU_metadata.IntegrationSigma.^2 * eye(3));
|
||||||
|
|
||||||
|
for imuIndex = IMUindices
|
||||||
|
accMeas = [ IMU_data(imuIndex).accelX; IMU_data(imuIndex).accelY; IMU_data(imuIndex).accelZ ];
|
||||||
|
omegaMeas = [ IMU_data(imuIndex).omegaX; IMU_data(imuIndex).omegaY; IMU_data(imuIndex).omegaZ ];
|
||||||
|
deltaT = IMU_data(imuIndex).dt;
|
||||||
|
currentSummarizedMeasurement.integrateMeasurement(accMeas, omegaMeas, deltaT);
|
||||||
|
end
|
||||||
|
|
||||||
|
% Create IMU factor
|
||||||
|
newFactors.add(ImuFactor( ...
|
||||||
|
currentPoseKey-1, currentVelKey-1, ...
|
||||||
|
currentPoseKey, currentVelKey, ...
|
||||||
|
currentBiasKey, currentSummarizedMeasurement, g, w_coriolis));
|
||||||
|
|
||||||
|
% Bias evolution as given in the IMU metadata
|
||||||
|
newFactors.add(BetweenFactorConstantBias(currentBiasKey-1, currentBiasKey, imuBias.ConstantBias(zeros(3,1), zeros(3,1)), ...
|
||||||
|
noiseModel.Diagonal.Sigmas(sqrt(numel(IMUindices)) * sigma_between_b)));
|
||||||
|
|
||||||
|
% Create GPS factor
|
||||||
|
GPSPose = Pose3(currentPoseGlobal.rotation, GPS_data(measurementIndex).Position);
|
||||||
|
if mod(measurementIndex, GPSskip) == 0
|
||||||
|
newFactors.add(PriorFactorPose3(currentPoseKey, GPSPose, noiseModelGPS));
|
||||||
|
end
|
||||||
|
|
||||||
|
% Add initial value
|
||||||
|
newValues.insert(currentPoseKey, GPSPose);
|
||||||
|
newValues.insert(currentVelKey, currentVelocityGlobal);
|
||||||
|
newValues.insert(currentBiasKey, currentBias);
|
||||||
|
|
||||||
|
% Update solver
|
||||||
|
% =======================================================================
|
||||||
|
% We accumulate 2*GPSskip GPS measurements before updating the solver at
|
||||||
|
% first so that the heading becomes observable.
|
||||||
|
if measurementIndex > firstGPSPose + 2*GPSskip
|
||||||
|
isam.update(newFactors, newValues);
|
||||||
|
newFactors = NonlinearFactorGraph;
|
||||||
|
newValues = Values;
|
||||||
|
|
||||||
|
if rem(measurementIndex,10)==0 % plot every 10 time steps
|
||||||
|
cla;
|
||||||
|
plot3DTrajectory(isam.calculateEstimate, 'g-');
|
||||||
|
title('Estimated trajectory using ISAM2 (IMU+GPS)')
|
||||||
|
xlabel('[m]')
|
||||||
|
ylabel('[m]')
|
||||||
|
zlabel('[m]')
|
||||||
|
axis equal
|
||||||
|
drawnow;
|
||||||
|
end
|
||||||
|
% =======================================================================
|
||||||
|
currentPoseGlobal = isam.calculateEstimate(currentPoseKey);
|
||||||
|
currentVelocityGlobal = isam.calculateEstimate(currentVelKey);
|
||||||
|
currentBias = isam.calculateEstimate(currentBiasKey);
|
||||||
|
end
|
||||||
|
end
|
||||||
|
|
||||||
|
end % end main loop
|
||||||
|
|
||||||
|
disp('-- Reached end of sensor data')
|
|
@ -1,126 +0,0 @@
|
||||||
%close all
|
|
||||||
%clc
|
|
||||||
|
|
||||||
import gtsam.*;
|
|
||||||
|
|
||||||
%% Read data
|
|
||||||
IMU_metadata = importdata(gtsam.findExampleDataFile('KittiEquivBiasedImu_metadata.txt'));
|
|
||||||
IMU_data = importdata(gtsam.findExampleDataFile('KittiEquivBiasedImu.txt'));
|
|
||||||
% Make text file column headers into struct fields
|
|
||||||
IMU_metadata = cell2struct(num2cell(IMU_metadata.data), IMU_metadata.colheaders, 2);
|
|
||||||
IMU_data = cell2struct(num2cell(IMU_data.data), IMU_data.colheaders, 2);
|
|
||||||
|
|
||||||
GPS_metadata = importdata(gtsam.findExampleDataFile('KittiGps_metadata.txt'));
|
|
||||||
GPS_data = importdata(gtsam.findExampleDataFile('KittiGps.txt'));
|
|
||||||
% Make text file column headers into struct fields
|
|
||||||
GPS_metadata = cell2struct(num2cell(GPS_metadata.data), GPS_metadata.colheaders, 2);
|
|
||||||
GPS_data = cell2struct(num2cell(GPS_data.data), GPS_data.colheaders, 2);
|
|
||||||
|
|
||||||
%% Convert GPS from lat/long to meters
|
|
||||||
[ x, y, ~ ] = deg2utm( [GPS_data.Latitude], [GPS_data.Longitude] );
|
|
||||||
for i = 1:numel(x)
|
|
||||||
GPS_data(i).Position = gtsam.Point3(x(i), y(i), GPS_data(i).Altitude);
|
|
||||||
end
|
|
||||||
|
|
||||||
% % Calculate GPS sigma in meters
|
|
||||||
% [ xSig, ySig, ~ ] = deg2utm( [GPS_data.Latitude] + [GPS_data.PositionSigma], ...
|
|
||||||
% [GPS_data.Longitude] + [GPS_data.PositionSigma]);
|
|
||||||
% xSig = xSig - x;
|
|
||||||
% ySig = ySig - y;
|
|
||||||
|
|
||||||
%% Start at time of first GPS measurement
|
|
||||||
firstGPSPose = 2;
|
|
||||||
|
|
||||||
%% Get initial conditions for the estimated trajectory
|
|
||||||
currentPoseGlobal = Pose3(Rot3, GPS_data(firstGPSPose).Position); % initial pose is the reference frame (navigation frame)
|
|
||||||
currentVelocityGlobal = LieVector([0;0;0]); % the vehicle is stationary at the beginning
|
|
||||||
currentBias = imuBias.ConstantBias(zeros(3,1), zeros(3,1));
|
|
||||||
|
|
||||||
%% Solver object
|
|
||||||
isamParams = ISAM2Params;
|
|
||||||
isamParams.setFactorization('QR');
|
|
||||||
isamParams.setRelinearizeSkip(1);
|
|
||||||
isam = gtsam.ISAM2(isamParams);
|
|
||||||
newFactors = NonlinearFactorGraph;
|
|
||||||
newValues = Values;
|
|
||||||
|
|
||||||
%% Create initial estimate and prior on initial pose, velocity, and biases
|
|
||||||
newValues.insert(symbol('x',firstGPSPose), currentPoseGlobal);
|
|
||||||
newValues.insert(symbol('v',firstGPSPose), currentVelocityGlobal);
|
|
||||||
newValues.insert(symbol('b',1), currentBias);
|
|
||||||
|
|
||||||
sigma_init_x = noiseModel.Diagonal.Precisions([0;0;0; 1;1;1]);
|
|
||||||
sigma_init_v = noiseModel.Isotropic.Sigma(3, 1000.0);
|
|
||||||
sigma_init_b = noiseModel.Isotropic.Sigma(6, 0.01);
|
|
||||||
|
|
||||||
newFactors.add(PriorFactorPose3(symbol('x',firstGPSPose), currentPoseGlobal, sigma_init_x));
|
|
||||||
newFactors.add(PriorFactorLieVector(symbol('v',firstGPSPose), currentVelocityGlobal, sigma_init_v));
|
|
||||||
newFactors.add(PriorFactorConstantBias(symbol('b',1), currentBias, sigma_init_b));
|
|
||||||
|
|
||||||
%% Main loop:
|
|
||||||
% (1) we read the measurements
|
|
||||||
% (2) we create the corresponding factors in the graph
|
|
||||||
% (3) we solve the graph to obtain and optimal estimate of robot trajectory
|
|
||||||
|
|
||||||
for poseIndex = firstGPSPose:length(GPS_data)
|
|
||||||
% At each non=IMU measurement we initialize a new node in the graph
|
|
||||||
currentPoseKey = symbol('x',poseIndex);
|
|
||||||
currentVelKey = symbol('v',poseIndex);
|
|
||||||
currentBiasKey = symbol('b',1);
|
|
||||||
|
|
||||||
if poseIndex > firstGPSPose
|
|
||||||
% Summarize IMU data between the previous GPS measurement and now
|
|
||||||
IMUindices = find([IMU_data.Time] > GPS_data(poseIndex-1).Time ...
|
|
||||||
& [IMU_data.Time] <= GPS_data(poseIndex).Time);
|
|
||||||
|
|
||||||
currentSummarizedMeasurement = gtsam.ImuFactorPreintegratedMeasurements( ...
|
|
||||||
currentBias, IMU_metadata.AccelerometerSigma.^2 * eye(3), ...
|
|
||||||
IMU_metadata.GyroscopeSigma.^2 * eye(3), IMU_metadata.IntegrationSigma.^2 * eye(3));
|
|
||||||
|
|
||||||
for imuIndex = IMUindices
|
|
||||||
accMeas = [ IMU_data(imuIndex).accelX; IMU_data(imuIndex).accelY; IMU_data(imuIndex).accelZ ];
|
|
||||||
omegaMeas = [ IMU_data(imuIndex).omegaX; IMU_data(imuIndex).omegaY; IMU_data(imuIndex).omegaZ ];
|
|
||||||
deltaT = IMU_data(imuIndex).dt;
|
|
||||||
currentSummarizedMeasurement.integrateMeasurement(accMeas, omegaMeas, deltaT);
|
|
||||||
end
|
|
||||||
|
|
||||||
% Create IMU factor
|
|
||||||
newFactors.add(ImuFactor( ...
|
|
||||||
currentPoseKey-1, currentVelKey-1, ...
|
|
||||||
currentPoseKey, currentVelKey, ...
|
|
||||||
currentBiasKey, currentSummarizedMeasurement, [0;0;-9.8], [0;0;0]));
|
|
||||||
|
|
||||||
% Create GPS factor
|
|
||||||
newFactors.add(PriorFactorPose3(currentPoseKey, Pose3(currentPoseGlobal.rotation, GPS_data(poseIndex).Position), ...
|
|
||||||
noiseModel.Diagonal.Precisions([ zeros(3,1); 1./(GPS_data(poseIndex).PositionSigma).^2*ones(3,1) ])));
|
|
||||||
|
|
||||||
% Add initial value
|
|
||||||
newValues.insert(currentPoseKey, Pose3(currentPoseGlobal.rotation, GPS_data(poseIndex).Position));
|
|
||||||
newValues.insert(currentVelKey, currentVelocityGlobal);
|
|
||||||
%newValues.insert(currentBiasKey, currentBias);
|
|
||||||
|
|
||||||
% Update solver
|
|
||||||
% =======================================================================
|
|
||||||
isam.update(newFactors, newValues);
|
|
||||||
newFactors = NonlinearFactorGraph;
|
|
||||||
newValues = Values;
|
|
||||||
|
|
||||||
cla;
|
|
||||||
plot3DTrajectory(isam.calculateEstimate, 'g-');
|
|
||||||
drawnow;
|
|
||||||
% =======================================================================
|
|
||||||
|
|
||||||
currentPoseGlobal = isam.calculateEstimate(currentPoseKey);
|
|
||||||
currentVelocityGlobal = isam.calculateEstimate(currentVelKey);
|
|
||||||
currentBias = isam.calculateEstimate(currentBiasKey);
|
|
||||||
|
|
||||||
end
|
|
||||||
end
|
|
||||||
|
|
||||||
disp('TODO: display results')
|
|
||||||
% figure(1)
|
|
||||||
% hold on;
|
|
||||||
% plot(positions(1,:), positions(2,:), '-b');
|
|
||||||
% plot3DTrajectory(isam.calculateEstimate, 'g-');
|
|
||||||
% axis equal;
|
|
||||||
% legend('true trajectory', 'traj integrated in body', 'traj integrated in nav')
|
|
|
@ -2,9 +2,11 @@ close all
|
||||||
clc
|
clc
|
||||||
|
|
||||||
import gtsam.*;
|
import gtsam.*;
|
||||||
|
disp('Example of application of ISAM2 for visual-inertial navigation on the KITTI VISION BENCHMARK SUITE (http://www.computervisiononline.com/dataset/kitti-vision-benchmark-suite)')
|
||||||
|
|
||||||
%% Read metadata and compute relative sensor pose transforms
|
%% Read metadata and compute relative sensor pose transforms
|
||||||
% IMU metadata
|
% IMU metadata
|
||||||
|
disp('-- Reading sensor metadata')
|
||||||
IMU_metadata = importdata('KittiEquivBiasedImu_metadata.txt');
|
IMU_metadata = importdata('KittiEquivBiasedImu_metadata.txt');
|
||||||
IMU_metadata = cell2struct(num2cell(IMU_metadata.data), IMU_metadata.colheaders, 2);
|
IMU_metadata = cell2struct(num2cell(IMU_metadata.data), IMU_metadata.colheaders, 2);
|
||||||
IMUinBody = Pose3.Expmap([IMU_metadata.BodyPtx; IMU_metadata.BodyPty; IMU_metadata.BodyPtz;
|
IMUinBody = Pose3.Expmap([IMU_metadata.BodyPtx; IMU_metadata.BodyPty; IMU_metadata.BodyPtz;
|
||||||
|
@ -20,25 +22,13 @@ VOinBody = Pose3.Expmap([VO_metadata.BodyPtx; VO_metadata.BodyPty; VO_metadata.B
|
||||||
VO_metadata.BodyPrx; VO_metadata.BodyPry; VO_metadata.BodyPrz; ]);
|
VO_metadata.BodyPrx; VO_metadata.BodyPry; VO_metadata.BodyPrz; ]);
|
||||||
VOinIMU = IMUinBody.inverse().compose(VOinBody);
|
VOinIMU = IMUinBody.inverse().compose(VOinBody);
|
||||||
|
|
||||||
% GPS metadata
|
|
||||||
GPS_metadata = importdata('KittiGps_metadata.txt');
|
|
||||||
GPS_metadata = cell2struct(num2cell(GPS_metadata.data), GPS_metadata.colheaders, 2);
|
|
||||||
GPSinBody = Pose3.Expmap([GPS_metadata.BodyPtx; GPS_metadata.BodyPty; GPS_metadata.BodyPtz;
|
|
||||||
GPS_metadata.BodyPrx; GPS_metadata.BodyPry; GPS_metadata.BodyPrz; ]);
|
|
||||||
GPSinIMU = IMUinBody.inverse().compose(GPSinBody);
|
|
||||||
|
|
||||||
%% Read data and change coordinate frame of GPS and VO measurements to IMU frame
|
%% Read data and change coordinate frame of GPS and VO measurements to IMU frame
|
||||||
|
disp('-- Reading sensor data from file')
|
||||||
% IMU data
|
% IMU data
|
||||||
IMU_data = importdata('KittiEquivBiasedImu.txt');
|
IMU_data = importdata('KittiEquivBiasedImu.txt');
|
||||||
IMU_data = cell2struct(num2cell(IMU_data.data), IMU_data.colheaders, 2);
|
IMU_data = cell2struct(num2cell(IMU_data.data), IMU_data.colheaders, 2);
|
||||||
imum = cellfun(@(x) x', num2cell([ [IMU_data.accelX]' [IMU_data.accelY]' [IMU_data.accelZ]' [IMU_data.omegaX]' [IMU_data.omegaY]' [IMU_data.omegaZ]' ], 2), 'UniformOutput', false);
|
imum = cellfun(@(x) x', num2cell([ [IMU_data.accelX]' [IMU_data.accelY]' [IMU_data.accelZ]' [IMU_data.omegaX]' [IMU_data.omegaY]' [IMU_data.omegaZ]' ], 2), 'UniformOutput', false);
|
||||||
[IMU_data.acc_omega] = deal(imum{:});
|
[IMU_data.acc_omega] = deal(imum{:});
|
||||||
%IMU_data = rmfield(IMU_data, { 'accelX' 'accelY' 'accelZ' 'omegaX' 'omegaY' 'omegaZ' });
|
|
||||||
sigma_init_x = noiseModel.Diagonal.Precisions([1;1;1; 1;1;1]);
|
|
||||||
sigma_init_v = noiseModel.Isotropic.Sigma(3, 1000.0);
|
|
||||||
sigma_init_b = noiseModel.Isotropic.Sigma(6, 0.01);
|
|
||||||
g = [0;0;-9.8];
|
|
||||||
w_coriolis = [0;0;0];
|
|
||||||
clear imum
|
clear imum
|
||||||
|
|
||||||
% VO data
|
% VO data
|
||||||
|
@ -54,32 +44,21 @@ VO_data = rmfield(VO_data, { 'dtx' 'dty' 'dtz' 'drx' 'dry' 'drz' });
|
||||||
noiseModelVO = noiseModel.Diagonal.Sigmas([ VO_metadata.RotationSigma * [1;1;1]; VO_metadata.TranslationSigma * [1;1;1] ]);
|
noiseModelVO = noiseModel.Diagonal.Sigmas([ VO_metadata.RotationSigma * [1;1;1]; VO_metadata.TranslationSigma * [1;1;1] ]);
|
||||||
clear logposes relposes
|
clear logposes relposes
|
||||||
|
|
||||||
% GPS data
|
|
||||||
GPS_data = importdata('KittiGps.txt');
|
|
||||||
GPS_data = cell2struct(num2cell(GPS_data.data), GPS_data.colheaders, 2);
|
|
||||||
% Convert GPS from lat/long to meters
|
|
||||||
[ x, y, ~ ] = deg2utm( [GPS_data.Latitude], [GPS_data.Longitude] );
|
|
||||||
for i = 1:numel(x)
|
|
||||||
GPS_data(i).Position = gtsam.Point3(x(i), y(i), GPS_data(i).Altitude);
|
|
||||||
end
|
|
||||||
% % Calculate GPS sigma in meters
|
|
||||||
% [ xSig, ySig, ~ ] = deg2utm( [GPS_data.Latitude] + [GPS_data.PositionSigma], ...
|
|
||||||
% [GPS_data.Longitude] + [GPS_data.PositionSigma]);
|
|
||||||
% xSig = xSig - x;
|
|
||||||
% ySig = ySig - y;
|
|
||||||
%% Start at time of first GPS measurement
|
|
||||||
% firstGPSPose = 1;
|
|
||||||
|
|
||||||
%% Get initial conditions for the estimated trajectory
|
%% Get initial conditions for the estimated trajectory
|
||||||
% currentPoseGlobal = Pose3(Rot3, GPS_data(firstGPSPose).Position); % initial pose is the reference frame (navigation frame)
|
|
||||||
currentPoseGlobal = Pose3;
|
currentPoseGlobal = Pose3;
|
||||||
currentVelocityGlobal = LieVector([0;0;0]); % the vehicle is stationary at the beginning
|
currentVelocityGlobal = LieVector([0;0;0]); % the vehicle is stationary at the beginning
|
||||||
currentBias = imuBias.ConstantBias(zeros(3,1), zeros(3,1));
|
currentBias = imuBias.ConstantBias(zeros(3,1), zeros(3,1));
|
||||||
|
sigma_init_x = noiseModel.Isotropic.Sigmas([ 1.0; 1.0; 0.01; 0.01; 0.01; 0.01 ]);
|
||||||
|
sigma_init_v = noiseModel.Isotropic.Sigma(3, 1000.0);
|
||||||
|
sigma_init_b = noiseModel.Isotropic.Sigmas([ 0.100; 0.100; 0.100; 5.00e-05; 5.00e-05; 5.00e-05 ]);
|
||||||
|
sigma_between_b = [ IMU_metadata.AccelerometerBiasSigma * ones(3,1); IMU_metadata.GyroscopeBiasSigma * ones(3,1) ];
|
||||||
|
g = [0;0;-9.8];
|
||||||
|
w_coriolis = [0;0;0];
|
||||||
|
|
||||||
%% Solver object
|
%% Solver object
|
||||||
isamParams = ISAM2Params;
|
isamParams = ISAM2Params;
|
||||||
isamParams.setFactorization('QR');
|
isamParams.setFactorization('CHOLESKY');
|
||||||
isamParams.setRelinearizeSkip(1);
|
isamParams.setRelinearizeSkip(10);
|
||||||
isam = gtsam.ISAM2(isamParams);
|
isam = gtsam.ISAM2(isamParams);
|
||||||
newFactors = NonlinearFactorGraph;
|
newFactors = NonlinearFactorGraph;
|
||||||
newValues = Values;
|
newValues = Values;
|
||||||
|
@ -88,13 +67,12 @@ newValues = Values;
|
||||||
% (1) we read the measurements
|
% (1) we read the measurements
|
||||||
% (2) we create the corresponding factors in the graph
|
% (2) we create the corresponding factors in the graph
|
||||||
% (3) we solve the graph to obtain and optimal estimate of robot trajectory
|
% (3) we solve the graph to obtain and optimal estimate of robot trajectory
|
||||||
timestamps = sortrows( [ ...
|
timestamps = [VO_data.Time]';
|
||||||
[VO_data.Time]' 1*ones(length([VO_data.Time]), 1); ...
|
|
||||||
%[GPS_data.Time]' 2*ones(length([GPS_data.Time]), 1); ...
|
|
||||||
], 1); % this are the time-stamps at which we want to initialize a new node in the graph
|
|
||||||
|
|
||||||
timestamps = timestamps(15:end,:); % there seem to be issues with the initial IMU measurements
|
timestamps = timestamps(15:end,:); % there seem to be issues with the initial IMU measurements
|
||||||
VOPoseKeys = []; % here we store the keys of the poses involved in VO (between) factors
|
IMUtimes = [IMU_data.Time];
|
||||||
|
|
||||||
|
disp('-- Starting main loop: inference is performed at each time step, but we plot trajectory every 100 steps')
|
||||||
|
|
||||||
for measurementIndex = 1:length(timestamps)
|
for measurementIndex = 1:length(timestamps)
|
||||||
|
|
||||||
|
@ -103,12 +81,6 @@ for measurementIndex = 1:length(timestamps)
|
||||||
currentVelKey = symbol('v',measurementIndex);
|
currentVelKey = symbol('v',measurementIndex);
|
||||||
currentBiasKey = symbol('b',measurementIndex);
|
currentBiasKey = symbol('b',measurementIndex);
|
||||||
t = timestamps(measurementIndex, 1);
|
t = timestamps(measurementIndex, 1);
|
||||||
type = timestamps(measurementIndex, 2);
|
|
||||||
|
|
||||||
%% bookkeeping
|
|
||||||
if type == 1 % we store the keys corresponding to VO measurements
|
|
||||||
VOPoseKeys = [VOPoseKeys; currentPoseKey];
|
|
||||||
end
|
|
||||||
|
|
||||||
if measurementIndex == 1
|
if measurementIndex == 1
|
||||||
%% Create initial estimate and prior on initial pose, velocity, and biases
|
%% Create initial estimate and prior on initial pose, velocity, and biases
|
||||||
|
@ -121,9 +93,8 @@ for measurementIndex = 1:length(timestamps)
|
||||||
else
|
else
|
||||||
t_previous = timestamps(measurementIndex-1, 1);
|
t_previous = timestamps(measurementIndex-1, 1);
|
||||||
%% Summarize IMU data between the previous GPS measurement and now
|
%% Summarize IMU data between the previous GPS measurement and now
|
||||||
IMUindices = find([IMU_data.Time] >= t_previous & [IMU_data.Time] <= t);
|
IMUindices = find(IMUtimes >= t_previous & IMUtimes <= t);
|
||||||
|
|
||||||
if ~isempty(IMUindices) % if there are IMU measurements to integrate
|
|
||||||
currentSummarizedMeasurement = gtsam.ImuFactorPreintegratedMeasurements( ...
|
currentSummarizedMeasurement = gtsam.ImuFactorPreintegratedMeasurements( ...
|
||||||
currentBias, IMU_metadata.AccelerometerSigma.^2 * eye(3), ...
|
currentBias, IMU_metadata.AccelerometerSigma.^2 * eye(3), ...
|
||||||
IMU_metadata.GyroscopeSigma.^2 * eye(3), IMU_metadata.IntegrationSigma.^2 * eye(3));
|
IMU_metadata.GyroscopeSigma.^2 * eye(3), IMU_metadata.IntegrationSigma.^2 * eye(3));
|
||||||
|
@ -141,28 +112,16 @@ for measurementIndex = 1:length(timestamps)
|
||||||
currentPoseKey, currentVelKey, ...
|
currentPoseKey, currentVelKey, ...
|
||||||
currentBiasKey, currentSummarizedMeasurement, g, w_coriolis));
|
currentBiasKey, currentSummarizedMeasurement, g, w_coriolis));
|
||||||
|
|
||||||
else % if there are no IMU measurements
|
|
||||||
error('no IMU measurements in [t_previous, t]')
|
|
||||||
end
|
|
||||||
|
|
||||||
% LC: sigma_init_b is wrong: this should be some uncertainty on bias evolution given in the IMU metadata
|
% LC: sigma_init_b is wrong: this should be some uncertainty on bias evolution given in the IMU metadata
|
||||||
newFactors.add(BetweenFactorConstantBias(currentBiasKey-1, currentBiasKey, imuBias.ConstantBias(zeros(3,1), zeros(3,1)), sigma_init_b));
|
newFactors.add(BetweenFactorConstantBias(currentBiasKey-1, currentBiasKey, imuBias.ConstantBias(zeros(3,1), zeros(3,1)), ...
|
||||||
|
noiseModel.Diagonal.Sigmas(sqrt(numel(IMUindices)) * sigma_between_b)));
|
||||||
%% Create GPS factor
|
|
||||||
if type == 2
|
|
||||||
newFactors.add(PriorFactorPose3(currentPoseKey, Pose3(currentPoseGlobal.rotation, GPS_data(measurementIndex).Position), ...
|
|
||||||
noiseModel.Diagonal.Precisions([ zeros(3,1); 1./(GPS_data(measurementIndex).PositionSigma).^2*ones(3,1) ])));
|
|
||||||
end
|
|
||||||
|
|
||||||
%% Create VO factor
|
%% Create VO factor
|
||||||
if type == 1
|
|
||||||
VOpose = VO_data(measurementIndex).RelativePose;
|
VOpose = VO_data(measurementIndex).RelativePose;
|
||||||
newFactors.add(BetweenFactorPose3(VOPoseKeys(end-1), VOPoseKeys(end), VOpose, noiseModelVO));
|
newFactors.add(BetweenFactorPose3(currentPoseKey - 1, currentPoseKey, VOpose, noiseModelVO));
|
||||||
end
|
|
||||||
|
|
||||||
% Add initial value
|
% Add initial value
|
||||||
% newValues.insert(currentPoseKey, Pose3(currentPoseGlobal.rotation, GPS_data(measurementIndex).Position));
|
newValues.insert(currentPoseKey, currentPoseGlobal.compose(VOpose));
|
||||||
newValues.insert(currentPoseKey,currentPoseGlobal);
|
|
||||||
newValues.insert(currentVelKey, currentVelocityGlobal);
|
newValues.insert(currentVelKey, currentVelocityGlobal);
|
||||||
newValues.insert(currentBiasKey, currentBias);
|
newValues.insert(currentBiasKey, currentBias);
|
||||||
|
|
||||||
|
@ -172,9 +131,13 @@ for measurementIndex = 1:length(timestamps)
|
||||||
newFactors = NonlinearFactorGraph;
|
newFactors = NonlinearFactorGraph;
|
||||||
newValues = Values;
|
newValues = Values;
|
||||||
|
|
||||||
if rem(measurementIndex,20)==0 % plot every 20 time steps
|
if rem(measurementIndex,100)==0 % plot every 100 time steps
|
||||||
cla;
|
cla;
|
||||||
plot3DTrajectory(isam.calculateEstimate, 'g-');
|
plot3DTrajectory(isam.calculateEstimate, 'g-');
|
||||||
|
title('Estimated trajectory using ISAM2 (IMU+VO)')
|
||||||
|
xlabel('[m]')
|
||||||
|
ylabel('[m]')
|
||||||
|
zlabel('[m]')
|
||||||
axis equal
|
axis equal
|
||||||
drawnow;
|
drawnow;
|
||||||
end
|
end
|
||||||
|
@ -185,3 +148,5 @@ for measurementIndex = 1:length(timestamps)
|
||||||
end
|
end
|
||||||
|
|
||||||
end % end main loop
|
end % end main loop
|
||||||
|
|
||||||
|
disp('-- Reached end of sensor data')
|
||||||
|
|
Loading…
Reference in New Issue