From 18a72718aa193126eaddd3f1f7db807e32247f05 Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Sun, 11 Aug 2013 19:29:01 +0000 Subject: [PATCH 1/7] Reenabled ISAM2 in SolverComparer --- examples/SolverComparer.cpp | 41 ++++++++++++++++++++++--------------- 1 file changed, 25 insertions(+), 16 deletions(-) diff --git a/examples/SolverComparer.cpp b/examples/SolverComparer.cpp index b46ea60b8..19281ce0f 100644 --- a/examples/SolverComparer.cpp +++ b/examples/SolverComparer.cpp @@ -165,10 +165,15 @@ int main(int argc, char *argv[]) { if(!datasetName.empty()) { cout << "Loading dataset " << datasetName << endl; - string datasetFile = findExampleDataFile(datasetName); - std::pair data = - load2D(datasetFile); - datasetMeasurements = *data.first; + try { + string datasetFile = findExampleDataFile(datasetName); + std::pair data = + load2D(datasetFile); + datasetMeasurements = *data.first; + } catch(std::exception& e) { + cout << e.what() << endl; + exit(1); + } } @@ -262,21 +267,23 @@ void runIncremental() // Initialize the new variable if(measurement->key1() > measurement->key2()) { - if(step == 1) - newVariables.insert(measurement->key1(), measurement->measured().inverse()); - else { - Pose prevPose = isam2.calculateEstimate(measurement->key2()); - newVariables.insert(measurement->key1(), prevPose * measurement->measured().inverse()); + if(!newVariables.exists(measurement->key1())) { // Only need to check newVariables since loop closures come after odometry + if(step == 1) + newVariables.insert(measurement->key1(), measurement->measured().inverse()); + else { + Pose prevPose = isam2.calculateEstimate(measurement->key2()); + newVariables.insert(measurement->key1(), prevPose * measurement->measured().inverse()); + } } - // cout << "Initializing " << step << endl; } else { - if(step == 1) - newVariables.insert(measurement->key2(), measurement->measured()); - else { - Pose prevPose = isam2.calculateEstimate(measurement->key1()); - newVariables.insert(measurement->key2(), prevPose * measurement->measured()); + if(!newVariables.exists(measurement->key1())) { // Only need to check newVariables since loop closures come after odometry + if(step == 1) + newVariables.insert(measurement->key2(), measurement->measured()); + else { + Pose prevPose = isam2.calculateEstimate(measurement->key1()); + newVariables.insert(measurement->key2(), prevPose * measurement->measured()); + } } - // cout << "Initializing " << step << endl; } } else if(BearingRangeFactor::shared_ptr measurement = @@ -348,6 +355,8 @@ void runIncremental() } } + tictoc_print_(); + // Compute marginals //try { // Marginals marginals(graph, values); From d46902ea062a068e32f6d0c9c3a7cc138c7af9ef Mon Sep 17 00:00:00 2001 From: Luca Carlone Date: Sun, 11 Aug 2013 22:45:58 +0000 Subject: [PATCH 2/7] Working IMUKitti example with VO only (slow!) --- matlab/gtsam_examples/IMUKittiExample.m | 209 ++++++++++++---------- matlab/gtsam_examples/IMUKittiExampleVO.m | 190 ++++++++++++++++++++ 2 files changed, 300 insertions(+), 99 deletions(-) create mode 100644 matlab/gtsam_examples/IMUKittiExampleVO.m diff --git a/matlab/gtsam_examples/IMUKittiExample.m b/matlab/gtsam_examples/IMUKittiExample.m index 92239353b..ec536bc17 100644 --- a/matlab/gtsam_examples/IMUKittiExample.m +++ b/matlab/gtsam_examples/IMUKittiExample.m @@ -6,24 +6,21 @@ 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; ]); +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; ]); +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; ]); +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); @@ -86,74 +83,85 @@ factors.add(PriorFactorLieVector(symbol('v',0), ... factors.add(PriorFactorConstantBias(symbol('b',0), ... imuBias.ConstantBias(bias_acc,bias_omega), noiseModel.Isotropic.Sigma(6, 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 - -% lastTime = 0; TODO: delete? -% lastIndex = 0; TODO: delete? currentSummarizedMeasurement = []; % Measurement types: % 1: VO % 2: GPS % 3: IMU -times = sortrows( [ ... +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); ... + %[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 -t_previous = 0; -poseIndex = 0; -for measurementIndex = 1:size(times,1) +%% 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 = times(measurementIndex, 1); - type = times(measurementIndex, 2); + 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 +% 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 % ======================================================================= @@ -178,46 +186,49 @@ for measurementIndex = 1:size(times,1) % ======================================================================= - %% 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; +% %% 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 -disp('TODO: display results') +figure +plot(position(:,1),position(:,2)) + + % figure(1) % hold on; % plot(positions(1,:), positions(2,:), '-b'); diff --git a/matlab/gtsam_examples/IMUKittiExampleVO.m b/matlab/gtsam_examples/IMUKittiExampleVO.m new file mode 100644 index 000000000..10bd33409 --- /dev/null +++ b/matlab/gtsam_examples/IMUKittiExampleVO.m @@ -0,0 +1,190 @@ +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' }); +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 + +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 = 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)); + +%% 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); ... + %[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 + +timestamps = timestamps(15:end,:); + +VOPoseKeys = []; + +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([IMU_data.Time] >= t_previous & [IMU_data.Time] <= 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 + + 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,20)==0 + 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 From 0320baf3f711a25876b1aba7a2c5030861231c10 Mon Sep 17 00:00:00 2001 From: Luca Carlone Date: Sun, 11 Aug 2013 22:57:54 +0000 Subject: [PATCH 3/7] Small updates in IMUKittiExampleVO --- matlab/gtsam_examples/IMUKittiExampleVO.m | 37 +++++++++++------------ 1 file changed, 17 insertions(+), 20 deletions(-) diff --git a/matlab/gtsam_examples/IMUKittiExampleVO.m b/matlab/gtsam_examples/IMUKittiExampleVO.m index 10bd33409..9541aff8d 100644 --- a/matlab/gtsam_examples/IMUKittiExampleVO.m +++ b/matlab/gtsam_examples/IMUKittiExampleVO.m @@ -4,6 +4,7 @@ clc import gtsam.*; %% Read metadata and compute relative sensor pose transforms +% IMU 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; @@ -12,20 +13,22 @@ 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; ]); - -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 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); @@ -38,6 +41,7 @@ g = [0;0;-9.8]; w_coriolis = [0;0;0]; 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 @@ -50,23 +54,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] ]); 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; +% firstGPSPose = 1; %% Get initial conditions for the estimated trajectory % currentPoseGlobal = Pose3(Rot3, GPS_data(firstGPSPose).Position); % initial pose is the reference frame (navigation frame) @@ -82,7 +84,6 @@ isam = gtsam.ISAM2(isamParams); newFactors = NonlinearFactorGraph; newValues = Values; - %% Main loop: % (1) we read the measurements % (2) we create the corresponding factors in the graph @@ -90,12 +91,10 @@ newValues = Values; 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 -timestamps = timestamps(15:end,:); - -VOPoseKeys = []; +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 for measurementIndex = 1:length(timestamps) @@ -128,7 +127,7 @@ for measurementIndex = 1:length(timestamps) 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 ]; @@ -146,6 +145,7 @@ for measurementIndex = 1:length(timestamps) 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 @@ -161,7 +161,7 @@ for measurementIndex = 1:length(timestamps) end % Add initial value - %newValues.insert(currentPoseKey, Pose3(currentPoseGlobal.rotation, GPS_data(measurementIndex).Position)); + % newValues.insert(currentPoseKey, Pose3(currentPoseGlobal.rotation, GPS_data(measurementIndex).Position)); newValues.insert(currentPoseKey,currentPoseGlobal); newValues.insert(currentVelKey, currentVelocityGlobal); newValues.insert(currentBiasKey, currentBias); @@ -172,19 +172,16 @@ for measurementIndex = 1:length(timestamps) newFactors = NonlinearFactorGraph; newValues = Values; - if rem(measurementIndex,20)==0 + if rem(measurementIndex,20)==0 % plot every 20 time steps cla; plot3DTrajectory(isam.calculateEstimate, 'g-'); axis equal drawnow; end - % ======================================================================= - + % ======================================================================= currentPoseGlobal = isam.calculateEstimate(currentPoseKey); currentVelocityGlobal = isam.calculateEstimate(currentVelKey); - currentBias = isam.calculateEstimate(currentBiasKey); - + currentBias = isam.calculateEstimate(currentBiasKey); end - - + end % end main loop From 14931bcc7d7b545b2a84cb8374e3ac26d82b1f06 Mon Sep 17 00:00:00 2001 From: Chris Beall Date: Mon, 12 Aug 2013 14:40:57 +0000 Subject: [PATCH 4/7] improved tests a little. basic 3 landmark test with smart projection factor fails! --- .../slam/tests/testSmartProjectionFactor.cpp | 27 +++++++++++-------- 1 file changed, 16 insertions(+), 11 deletions(-) diff --git a/gtsam_unstable/slam/tests/testSmartProjectionFactor.cpp b/gtsam_unstable/slam/tests/testSmartProjectionFactor.cpp index e64d08e7d..5b161c757 100644 --- a/gtsam_unstable/slam/tests/testSmartProjectionFactor.cpp +++ b/gtsam_unstable/slam/tests/testSmartProjectionFactor.cpp @@ -166,8 +166,8 @@ TEST( SmartProjectionFactor, noisy ){ /* ************************************************************************* */ -TEST( SmartProjectionFactor, 3poses ){ - cout << " ************************ MultiProjectionFactor: 3 cams + 3 landmarks **********************" << endl; +TEST( SmartProjectionFactor, 3poses_smart_projection_factor ){ + cout << " ************************ SmartProjectionFactor: 3 cams + 3 landmarks **********************" << endl; Symbol x1('X', 1); Symbol x2('X', 2); @@ -232,17 +232,19 @@ TEST( SmartProjectionFactor, 3poses ){ graph.add(PriorFactor(x1, pose1, noisePrior)); graph.add(PriorFactor(x2, pose2, noisePrior)); - Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); +// Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/10, 0., -M_PI/10), gtsam::Point3(0.5,0.1,0.3)); // noise from regular projection factor test below + Pose3 noise_pose = Pose3(Rot3::ypr(-M_PI/100, 0., -M_PI/100), gtsam::Point3(0.1,0.1,0.1)); // smaller noise Values values; values.insert(x1, pose1); - values.insert(x2, pose2*noise_pose); - values.insert(x3, pose3); + values.insert(x2, pose2); + // initialize third pose with some noise, we expect it to move back to original pose3 + values.insert(x3, pose3*noise_pose); + values.at(x3).print("Smart: Pose3 before optimization: "); LevenbergMarquardtParams params; params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; params.verbosity = NonlinearOptimizerParams::ERROR; - Values result; gttic_(SmartProjectionFactor); LevenbergMarquardtOptimizer optimizer(graph, values, params); @@ -250,7 +252,9 @@ TEST( SmartProjectionFactor, 3poses ){ gttoc_(SmartProjectionFactor); tictoc_finishedIteration_(); - result.print("results of 3 camera, 3 landmark optimization \n"); + // result.print("results of 3 camera, 3 landmark optimization \n"); + result.at(x3).print("Smart: Pose3 after optimization: "); + EXPECT(assert_equal(pose3,result.at(x3))); tictoc_print_(); } @@ -258,7 +262,7 @@ TEST( SmartProjectionFactor, 3poses ){ /* ************************************************************************* */ TEST( SmartProjectionFactor, 3poses_projection_factor ){ - cout << " ************************ Normal ProjectionFactor: 3 cams + 3 landmarks **********************" << endl; +// cout << " ************************ Normal ProjectionFactor: 3 cams + 3 landmarks **********************" << endl; Symbol x1('X', 1); Symbol x2('X', 2); @@ -280,7 +284,6 @@ TEST( SmartProjectionFactor, 3poses_projection_factor ){ // create third camera 1 meter above the first camera Pose3 pose3 = pose1 * Pose3(Rot3(), Point3(0,-1,0)); - pose3.print("Pose3: "); SimpleCamera cam3(pose3, *K); // three landmarks ~5 meters infront of camera @@ -317,6 +320,7 @@ TEST( SmartProjectionFactor, 3poses_projection_factor ){ values.insert(L(1), landmark1); values.insert(L(2), landmark2); values.insert(L(3), landmark3); +// values.at(x3).print("Pose3 before optimization: "); LevenbergMarquardtParams params; // params.verbosityLM = LevenbergMarquardtParams::TRYLAMBDA; @@ -324,14 +328,15 @@ TEST( SmartProjectionFactor, 3poses_projection_factor ){ LevenbergMarquardtOptimizer optimizer(graph, values, params); Values result = optimizer.optimize(); - result.print("Regular Projection Factor: results of 3 camera, 3 landmark optimization \n"); +// result.at(x3).print("Pose3 after optimization: "); + EXPECT(assert_equal(pose3,result.at(x3))); } /* ************************************************************************* */ TEST( SmartProjectionFactor, Hessian ){ - cout << " ************************ Normal ProjectionFactor: Hessian **********************" << endl; + cout << " ************************ SmartProjectionFactor: Hessian **********************" << endl; Symbol x1('X', 1); Symbol x2('X', 2); From 87a7c56c88edd4f5ea1ed41f616e7c2aeec4d535 Mon Sep 17 00:00:00 2001 From: Vadim Indelman Date: Mon, 12 Aug 2013 16:11:48 +0000 Subject: [PATCH 5/7] Switched to square root of covariance norm. --- gtsam_unstable/slam/BetweenFactorEM.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam_unstable/slam/BetweenFactorEM.h b/gtsam_unstable/slam/BetweenFactorEM.h index 5cfefca0d..9c3736387 100644 --- a/gtsam_unstable/slam/BetweenFactorEM.h +++ b/gtsam_unstable/slam/BetweenFactorEM.h @@ -232,8 +232,8 @@ namespace gtsam { Matrix invCov_inlier = model_inlier_->R().transpose() * model_inlier_->R(); Matrix invCov_outlier = model_outlier_->R().transpose() * model_outlier_->R(); - double p_inlier = prior_inlier_ * invCov_inlier.norm() * exp( -0.5 * err_wh_inlier.dot(err_wh_inlier) ); - double p_outlier = prior_outlier_ * invCov_outlier.norm() * exp( -0.5 * err_wh_outlier.dot(err_wh_outlier) ); + double p_inlier = prior_inlier_ * sqrt(invCov_inlier.norm()) * exp( -0.5 * err_wh_inlier.dot(err_wh_inlier) ); + double p_outlier = prior_outlier_ * sqrt(invCov_outlier.norm()) * exp( -0.5 * err_wh_outlier.dot(err_wh_outlier) ); double sumP = p_inlier + p_outlier; p_inlier /= sumP; From 7a027be7e55c96200a32b62d170ce64063d3edbd Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Mon, 12 Aug 2013 16:25:13 +0000 Subject: [PATCH 6/7] Fixed unit tests compiling on windows --- .../testConcurrentIncrementalSmootherDL.cpp | 24 +++++++++---------- .../testConcurrentIncrementalSmootherGN.cpp | 24 +++++++++---------- gtsam_unstable/slam/BetweenFactorEM.h | 10 ++++---- .../slam/tests/testBetweenFactorEM.cpp | 4 ++-- 4 files changed, 31 insertions(+), 31 deletions(-) diff --git a/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherDL.cpp b/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherDL.cpp index ca6a89380..0b91644e2 100644 --- a/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherDL.cpp +++ b/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherDL.cpp @@ -73,7 +73,7 @@ Values BatchOptimize(const NonlinearFactorGraph& graph, const Values& theta, int /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, equals ) +TEST( ConcurrentIncrementalSmootherDL, equals ) { // TODO: Test 'equals' more vigorously @@ -99,7 +99,7 @@ TEST( ConcurrentIncrementalSmoother, equals ) } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, getFactors ) +TEST( ConcurrentIncrementalSmootherDL, getFactors ) { // Create a Concurrent Batch Smoother ISAM2Params parameters; @@ -150,7 +150,7 @@ TEST( ConcurrentIncrementalSmoother, getFactors ) } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, getLinearizationPoint ) +TEST( ConcurrentIncrementalSmootherDL, getLinearizationPoint ) { // Create a Concurrent Batch Smoother ISAM2Params parameters; @@ -201,19 +201,19 @@ TEST( ConcurrentIncrementalSmoother, getLinearizationPoint ) } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, getOrdering ) +TEST( ConcurrentIncrementalSmootherDL, getOrdering ) { // TODO: Think about how to check ordering... } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, getDelta ) +TEST( ConcurrentIncrementalSmootherDL, getDelta ) { // TODO: Think about how to check ordering... } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, calculateEstimate ) +TEST( ConcurrentIncrementalSmootherDL, calculateEstimate ) { // Create a Concurrent Batch Smoother ISAM2Params parameters; @@ -287,7 +287,7 @@ TEST( ConcurrentIncrementalSmoother, calculateEstimate ) } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, update_empty ) +TEST( ConcurrentIncrementalSmootherDL, update_empty ) { // Create a set of optimizer parameters ISAM2Params parameters; @@ -300,7 +300,7 @@ TEST( ConcurrentIncrementalSmoother, update_empty ) } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, update_multiple ) +TEST( ConcurrentIncrementalSmootherDL, update_multiple ) { // Create a Concurrent Batch Smoother ISAM2Params parameters; @@ -358,7 +358,7 @@ TEST( ConcurrentIncrementalSmoother, update_multiple ) } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, synchronize_empty ) +TEST( ConcurrentIncrementalSmootherDL, synchronize_empty ) { // Create a set of optimizer parameters ISAM2Params parameters; @@ -388,7 +388,7 @@ TEST( ConcurrentIncrementalSmoother, synchronize_empty ) } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, synchronize_1 ) +TEST( ConcurrentIncrementalSmootherDL, synchronize_1 ) { // Create a set of optimizer parameters ISAM2Params parameters; @@ -450,7 +450,7 @@ TEST( ConcurrentIncrementalSmoother, synchronize_1 ) /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, synchronize_2 ) +TEST( ConcurrentIncrementalSmootherDL, synchronize_2 ) { // Create a set of optimizer parameters ISAM2Params parameters; @@ -531,7 +531,7 @@ TEST( ConcurrentIncrementalSmoother, synchronize_2 ) /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, synchronize_3 ) +TEST( ConcurrentIncrementalSmootherDL, synchronize_3 ) { // Create a set of optimizer parameters ISAM2Params parameters; diff --git a/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherGN.cpp b/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherGN.cpp index 5c608b2cb..bdca9238c 100644 --- a/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherGN.cpp +++ b/gtsam_unstable/nonlinear/tests/testConcurrentIncrementalSmootherGN.cpp @@ -73,7 +73,7 @@ Values BatchOptimize(const NonlinearFactorGraph& graph, const Values& theta, int /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, equals ) +TEST( ConcurrentIncrementalSmootherGN, equals ) { // TODO: Test 'equals' more vigorously @@ -99,7 +99,7 @@ TEST( ConcurrentIncrementalSmoother, equals ) } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, getFactors ) +TEST( ConcurrentIncrementalSmootherGN, getFactors ) { // Create a Concurrent Batch Smoother ISAM2Params parameters; @@ -150,7 +150,7 @@ TEST( ConcurrentIncrementalSmoother, getFactors ) } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, getLinearizationPoint ) +TEST( ConcurrentIncrementalSmootherGN, getLinearizationPoint ) { // Create a Concurrent Batch Smoother ISAM2Params parameters; @@ -201,19 +201,19 @@ TEST( ConcurrentIncrementalSmoother, getLinearizationPoint ) } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, getOrdering ) +TEST( ConcurrentIncrementalSmootherGN, getOrdering ) { // TODO: Think about how to check ordering... } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, getDelta ) +TEST( ConcurrentIncrementalSmootherGN, getDelta ) { // TODO: Think about how to check ordering... } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, calculateEstimate ) +TEST( ConcurrentIncrementalSmootherGN, calculateEstimate ) { // Create a Concurrent Batch Smoother ISAM2Params parameters; @@ -287,7 +287,7 @@ TEST( ConcurrentIncrementalSmoother, calculateEstimate ) } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, update_empty ) +TEST( ConcurrentIncrementalSmootherGN, update_empty ) { // Create a set of optimizer parameters ISAM2Params parameters; @@ -300,7 +300,7 @@ TEST( ConcurrentIncrementalSmoother, update_empty ) } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, update_multiple ) +TEST( ConcurrentIncrementalSmootherGN, update_multiple ) { // Create a Concurrent Batch Smoother ISAM2Params parameters; @@ -358,7 +358,7 @@ TEST( ConcurrentIncrementalSmoother, update_multiple ) } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, synchronize_empty ) +TEST( ConcurrentIncrementalSmootherGN, synchronize_empty ) { // Create a set of optimizer parameters ISAM2Params parameters; @@ -388,7 +388,7 @@ TEST( ConcurrentIncrementalSmoother, synchronize_empty ) } /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, synchronize_1 ) +TEST( ConcurrentIncrementalSmootherGN, synchronize_1 ) { // Create a set of optimizer parameters ISAM2Params parameters; @@ -450,7 +450,7 @@ TEST( ConcurrentIncrementalSmoother, synchronize_1 ) /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, synchronize_2 ) +TEST( ConcurrentIncrementalSmootherGN, synchronize_2 ) { // Create a set of optimizer parameters ISAM2Params parameters; @@ -531,7 +531,7 @@ TEST( ConcurrentIncrementalSmoother, synchronize_2 ) /* ************************************************************************* */ -TEST( ConcurrentIncrementalSmoother, synchronize_3 ) +TEST( ConcurrentIncrementalSmootherGN, synchronize_3 ) { // Create a set of optimizer parameters ISAM2Params parameters; diff --git a/gtsam_unstable/slam/BetweenFactorEM.h b/gtsam_unstable/slam/BetweenFactorEM.h index 9c3736387..9eb253f22 100644 --- a/gtsam_unstable/slam/BetweenFactorEM.h +++ b/gtsam_unstable/slam/BetweenFactorEM.h @@ -165,17 +165,17 @@ namespace gtsam { Vector err_wh_eq; err_wh_eq.resize(err_wh_inlier.rows()*2); - err_wh_eq << sqrt(p_inlier) * err_wh_inlier.array() , sqrt(p_outlier) * err_wh_outlier.array(); + err_wh_eq << std::sqrt(p_inlier) * err_wh_inlier.array() , std::sqrt(p_outlier) * err_wh_outlier.array(); if (H){ // stack Jacobians for the two indicators for each of the key - Matrix H1_inlier = sqrt(p_inlier)*model_inlier_->Whiten(H1); - Matrix H1_outlier = sqrt(p_outlier)*model_outlier_->Whiten(H1); + Matrix H1_inlier = std::sqrt(p_inlier)*model_inlier_->Whiten(H1); + Matrix H1_outlier = std::sqrt(p_outlier)*model_outlier_->Whiten(H1); Matrix H1_aug = gtsam::stack(2, &H1_inlier, &H1_outlier); - Matrix H2_inlier = sqrt(p_inlier)*model_inlier_->Whiten(H2); - Matrix H2_outlier = sqrt(p_outlier)*model_outlier_->Whiten(H2); + Matrix H2_inlier = std::sqrt(p_inlier)*model_inlier_->Whiten(H2); + Matrix H2_outlier = std::sqrt(p_outlier)*model_outlier_->Whiten(H2); Matrix H2_aug = gtsam::stack(2, &H2_inlier, &H2_outlier); (*H)[0].resize(H1_aug.rows(),H1_aug.cols()); diff --git a/gtsam_unstable/slam/tests/testBetweenFactorEM.cpp b/gtsam_unstable/slam/tests/testBetweenFactorEM.cpp index 08cbb856c..c7772a125 100644 --- a/gtsam_unstable/slam/tests/testBetweenFactorEM.cpp +++ b/gtsam_unstable/slam/tests/testBetweenFactorEM.cpp @@ -104,7 +104,7 @@ TEST( BetweenFactorEM, EvaluateError) Vector actual_err_wh_outlier = Vector_(3, actual_err_wh[3], actual_err_wh[4], actual_err_wh[5]); // in case of inlier, inlier-mode whitented error should be dominant - assert(actual_err_wh_inlier.norm() > 1000.0*actual_err_wh_outlier.norm()); + CHECK(actual_err_wh_inlier.norm() > 1000.0*actual_err_wh_outlier.norm()); cout << "Inlier test. norm of actual_err_wh_inlier, actual_err_wh_outlier: "< Date: Mon, 12 Aug 2013 20:45:44 +0000 Subject: [PATCH 7/7] Fixed GPS Kitti example, VO works but bad results --- matlab/gtsam_examples/IMUKittiExample.m | 237 ------------------ .../gtsam_examples/IMUKittiExampleAdvanced.m | 191 ++++++++++++++ matlab/gtsam_examples/IMUKittiExampleGPS.m | 149 +++++++++++ matlab/gtsam_examples/IMUKittiExampleSimple.m | 126 ---------- matlab/gtsam_examples/IMUKittiExampleVO.m | 119 ++++----- 5 files changed, 382 insertions(+), 440 deletions(-) delete mode 100644 matlab/gtsam_examples/IMUKittiExample.m create mode 100644 matlab/gtsam_examples/IMUKittiExampleAdvanced.m create mode 100644 matlab/gtsam_examples/IMUKittiExampleGPS.m delete mode 100644 matlab/gtsam_examples/IMUKittiExampleSimple.m diff --git a/matlab/gtsam_examples/IMUKittiExample.m b/matlab/gtsam_examples/IMUKittiExample.m deleted file mode 100644 index ec536bc17..000000000 --- a/matlab/gtsam_examples/IMUKittiExample.m +++ /dev/null @@ -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') diff --git a/matlab/gtsam_examples/IMUKittiExampleAdvanced.m b/matlab/gtsam_examples/IMUKittiExampleAdvanced.m new file mode 100644 index 000000000..1db60a5ad --- /dev/null +++ b/matlab/gtsam_examples/IMUKittiExampleAdvanced.m @@ -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 diff --git a/matlab/gtsam_examples/IMUKittiExampleGPS.m b/matlab/gtsam_examples/IMUKittiExampleGPS.m new file mode 100644 index 000000000..49f01befe --- /dev/null +++ b/matlab/gtsam_examples/IMUKittiExampleGPS.m @@ -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') diff --git a/matlab/gtsam_examples/IMUKittiExampleSimple.m b/matlab/gtsam_examples/IMUKittiExampleSimple.m deleted file mode 100644 index f3940a4b4..000000000 --- a/matlab/gtsam_examples/IMUKittiExampleSimple.m +++ /dev/null @@ -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') diff --git a/matlab/gtsam_examples/IMUKittiExampleVO.m b/matlab/gtsam_examples/IMUKittiExampleVO.m index 9541aff8d..6434e750a 100644 --- a/matlab/gtsam_examples/IMUKittiExampleVO.m +++ b/matlab/gtsam_examples/IMUKittiExampleVO.m @@ -2,9 +2,11 @@ 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; @@ -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; ]); 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' }); -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 % 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] ]); 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.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 isamParams = ISAM2Params; -isamParams.setFactorization('QR'); -isamParams.setRelinearizeSkip(1); +isamParams.setFactorization('CHOLESKY'); +isamParams.setRelinearizeSkip(10); isam = gtsam.ISAM2(isamParams); newFactors = NonlinearFactorGraph; newValues = Values; @@ -88,13 +67,12 @@ newValues = Values; % (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 = [VO_data.Time]'; 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) @@ -103,12 +81,6 @@ for measurementIndex = 1:length(timestamps) 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 @@ -121,48 +93,35 @@ for measurementIndex = 1:length(timestamps) else t_previous = timestamps(measurementIndex-1, 1); %% 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( ... - 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]') + 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)); + % 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 + newFactors.add(BetweenFactorConstantBias(currentBiasKey-1, currentBiasKey, imuBias.ConstantBias(zeros(3,1), zeros(3,1)), ... + noiseModel.Diagonal.Sigmas(sqrt(numel(IMUindices)) * sigma_between_b))); %% Create VO factor - if type == 1 VOpose = VO_data(measurementIndex).RelativePose; - newFactors.add(BetweenFactorPose3(VOPoseKeys(end-1), VOPoseKeys(end), VOpose, noiseModelVO)); - end + newFactors.add(BetweenFactorPose3(currentPoseKey - 1, currentPoseKey, VOpose, noiseModelVO)); % Add initial value - % newValues.insert(currentPoseKey, Pose3(currentPoseGlobal.rotation, GPS_data(measurementIndex).Position)); - newValues.insert(currentPoseKey,currentPoseGlobal); + newValues.insert(currentPoseKey, currentPoseGlobal.compose(VOpose)); newValues.insert(currentVelKey, currentVelocityGlobal); newValues.insert(currentBiasKey, currentBias); @@ -172,9 +131,13 @@ for measurementIndex = 1:length(timestamps) newFactors = NonlinearFactorGraph; newValues = Values; - if rem(measurementIndex,20)==0 % plot every 20 time steps + if rem(measurementIndex,100)==0 % plot every 100 time steps cla; plot3DTrajectory(isam.calculateEstimate, 'g-'); + title('Estimated trajectory using ISAM2 (IMU+VO)') + xlabel('[m]') + ylabel('[m]') + zlabel('[m]') axis equal drawnow; end @@ -185,3 +148,5 @@ for measurementIndex = 1:length(timestamps) end end % end main loop + +disp('-- Reached end of sensor data')