Cleaned up spurious import statements

release/4.3a0
Frank Dellaert 2013-06-20 06:49:56 +00:00
parent c7e79fb546
commit 278c116785
4 changed files with 8 additions and 14 deletions

View File

@ -2,8 +2,9 @@ function [data,truth] = VisualISAMGenerateData(options)
% VisualISAMGenerateData creates data for viusalSLAM::iSAM examples
% Authors: Duy Nguyen Ta and Frank Dellaert
%% Generate simulated data
import gtsam.*
%% Generate simulated data
if options.triangle % Create a triangle target, just 3 points on a plane
nrPoints = 3;
r = 10;
@ -24,7 +25,6 @@ else % 3D landmarks as vertices of a cube
end
%% Create camera cameras on a circle around the triangle
import gtsam.*
height = 10; r = 40;
truth.K = Cal3_S2(500,500,0,640/2,480/2);
data.K = truth.K;

View File

@ -2,16 +2,16 @@ function [noiseModels,isam,result,nextPoseIndex] = VisualISAMInitialize(data,tru
% VisualISAMInitialize initializes visualSLAM::iSAM object and noise parameters
% Authors: Duy Nguyen Ta, Frank Dellaert and Alex Cunningham
%% Initialize iSAM
import gtsam.*
%% Initialize iSAM
params = gtsam.ISAM2Params;
if options.alwaysRelinearize
params.setRelinearizeSkip(1);
end
isam = ISAM2;
isam = ISAM2(params);
%% Set Noise parameters
import gtsam.*
noiseModels.pose = noiseModel.Diagonal.Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]');
%noiseModels.odometry = noiseModel.Diagonal.Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]');
noiseModels.odometry = noiseModel.Diagonal.Sigmas([0.05 0.05 0.05 0.2 0.2 0.2]');
@ -20,7 +20,6 @@ noiseModels.measurement = noiseModel.Isotropic.Sigma(2, 1.0);
%% Add constraints/priors
% TODO: should not be from ground truth!
import gtsam.*
newFactors = NonlinearFactorGraph;
initialEstimates = Values;
for i=1:2
@ -38,7 +37,6 @@ end
nextPoseIndex = 3;
%% Add visual measurement factors from two first poses and initialize observed landmarks
import gtsam.*
for i=1:2
ii = symbol('x',i);
for k=1:length(data.Z{i})
@ -56,11 +54,9 @@ for i=1:2
end
%% Add odometry between frames 1 and 2
import gtsam.*
newFactors.add(BetweenFactorPose3(symbol('x',1), symbol('x',2), data.odometry{1}, noiseModels.odometry));
%% Update ISAM
import gtsam.*
if options.batchInitialization % Do a full optimize for first two poses
batchOptimizer = LevenbergMarquardtOptimizer(newFactors, initialEstimates);
fullyOptimized = batchOptimizer.optimize();

View File

@ -2,6 +2,7 @@ function VisualISAMPlot(truth, data, isam, result, options)
% VisualISAMPlot plots current state of ISAM2 object
% Authors: Duy Nguyen Ta and Frank Dellaert
import gtsam.*
h=gca;
cla(h);
hold on;
@ -12,7 +13,6 @@ marginals = Marginals(isam.getFactorsUnsafe(), isam.calculateEstimate()); % TODO
gtsam.plot3DPoints(result, [], marginals);
%% Plot cameras
import gtsam.*
M = 1;
while result.exists(symbol('x',M))
ii = symbol('x',M);

View File

@ -2,19 +2,18 @@ function [isam,result,nextPoseIndex] = VisualISAMStep(data,noiseModels,isam,resu
% VisualISAMStep executes one update step of visualSLAM::iSAM object
% Authors: Duy Nguyen Ta and Frank Dellaert
import gtsam.*
% iSAM expects us to give it a new set of factors
% along with initial estimates for any new variables introduced.
import gtsam.*
newFactors = NonlinearFactorGraph;
initialEstimates = Values;
%% Add odometry
import gtsam.*
odometry = data.odometry{nextPoseIndex-1};
newFactors.add(BetweenFactorPose3(symbol('x',nextPoseIndex-1), symbol('x',nextPoseIndex), odometry, noiseModels.odometry));
%% Add visual measurement factors and initializations as necessary
import gtsam.*
for k=1:length(data.Z{nextPoseIndex})
zij = data.Z{nextPoseIndex}{k};
j = data.J{nextPoseIndex}{k};
@ -28,7 +27,6 @@ for k=1:length(data.Z{nextPoseIndex})
end
%% Initial estimates for the new pose.
import gtsam.*
prevPose = result.at(symbol('x',nextPoseIndex-1));
initialEstimates.insert(symbol('x',nextPoseIndex), prevPose.compose(odometry));