Working IMUKitti example with VO only (slow!)
parent
18a72718aa
commit
d46902ea06
|
@ -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');
|
||||
|
|
|
@ -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
|
Loading…
Reference in New Issue