Skip to content

Commit

Permalink
adapt examples to new direct member access
Browse files Browse the repository at this point in the history
  • Loading branch information
senselessDev committed Jan 29, 2022
1 parent 11b2135 commit 65d72ab
Show file tree
Hide file tree
Showing 12 changed files with 12 additions and 12 deletions.
2 changes: 1 addition & 1 deletion matlab/+gtsam/VisualISAMInitialize.m
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@
%% Initialize iSAM
params = gtsam.ISAM2Params;
if options.alwaysRelinearize
params.setRelinearizeSkip(1);
params.relinearizeSkip = 1;
end
isam = ISAM2(params);

Expand Down
2 changes: 1 addition & 1 deletion matlab/gtsam_examples/IMUKittiExampleGPS.m
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@
%% Solver object
isamParams = ISAM2Params;
isamParams.setFactorization('CHOLESKY');
isamParams.setRelinearizeSkip(10);
isamParams.relinearizeSkip = 10;
isam = gtsam.ISAM2(isamParams);
newFactors = NonlinearFactorGraph;
newValues = Values;
Expand Down
2 changes: 1 addition & 1 deletion matlab/unstable_examples/+imuSimulator/IMUComparison.m
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@

%% Solver object
isamParams = ISAM2Params;
isamParams.setRelinearizeSkip(1);
isamParams.relinearizeSkip = 1;
isam = gtsam.ISAM2(isamParams);

initialValues = Values;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@

%% Solver object
isamParams = ISAM2Params;
isamParams.setRelinearizeSkip(1);
isamParams.relinearizeSkip = 1;
isam = gtsam.ISAM2(isamParams);

sigma_init_x = 1.0;
Expand Down
2 changes: 1 addition & 1 deletion matlab/unstable_examples/+imuSimulator/coriolisExample.m
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@
% Solver object
isamParams = ISAM2Params;
isamParams.setFactorization('CHOLESKY');
isamParams.setRelinearizeSkip(10);
isamParams.relinearizeSkip = 10;
isam = gtsam.ISAM2(isamParams);
newFactors = NonlinearFactorGraph;
newValues = Values;
Expand Down
2 changes: 1 addition & 1 deletion matlab/unstable_examples/IMUKittiExampleAdvanced.m
Original file line number Diff line number Diff line change
Expand Up @@ -82,7 +82,7 @@
%% Solver object
isamParams = ISAM2Params;
isamParams.setFactorization('QR');
isamParams.setRelinearizeSkip(1);
isamParams.relinearizeSkip = 1;
isam = gtsam.ISAM2(isamParams);
newFactors = NonlinearFactorGraph;
newValues = Values;
Expand Down
2 changes: 1 addition & 1 deletion matlab/unstable_examples/IMUKittiExampleVO.m
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@
%% Solver object
isamParams = ISAM2Params;
isamParams.setFactorization('CHOLESKY');
isamParams.setRelinearizeSkip(10);
isamParams.relinearizeSkip = 10;
isam = gtsam.ISAM2(isamParams);
newFactors = NonlinearFactorGraph;
newValues = Values;
Expand Down
2 changes: 1 addition & 1 deletion python/gtsam/examples/IMUKittiExampleGPS.py
Original file line number Diff line number Diff line change
Expand Up @@ -203,7 +203,7 @@ def optimize(gps_measurements: List[GpsMeasurement],
# Set ISAM2 parameters and create ISAM2 solver object
isam_params = gtsam.ISAM2Params()
isam_params.setFactorization("CHOLESKY")
isam_params.setRelinearizeSkip(10)
isam_params.relinearizeSkip = 10

isam = gtsam.ISAM2(isam_params)

Expand Down
2 changes: 1 addition & 1 deletion python/gtsam/examples/Pose2ISAM2Example.py
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,7 @@ def Pose2SLAM_ISAM2_example():
# update calls are required to perform the relinearization.
parameters = gtsam.ISAM2Params()
parameters.setRelinearizeThreshold(0.1)
parameters.setRelinearizeSkip(1)
parameters.relinearizeSkip = 1
isam = gtsam.ISAM2(parameters)

# Create the ground truth odometry measurements of the robot during the trajectory.
Expand Down
2 changes: 1 addition & 1 deletion python/gtsam/examples/Pose3ISAM2Example.py
Original file line number Diff line number Diff line change
Expand Up @@ -140,7 +140,7 @@ def Pose3_ISAM2_example():
# update calls are required to perform the relinearization.
parameters = gtsam.ISAM2Params()
parameters.setRelinearizeThreshold(0.1)
parameters.setRelinearizeSkip(1)
parameters.relinearizeSkip = 1
isam = gtsam.ISAM2(parameters)

# Create the ground truth poses of the robot trajectory.
Expand Down
2 changes: 1 addition & 1 deletion python/gtsam/examples/VisualISAM2Example.py
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ def visual_ISAM2_example():
# will approach the batch result.
parameters = gtsam.ISAM2Params()
parameters.setRelinearizeThreshold(0.01)
parameters.setRelinearizeSkip(1)
parameters.relinearizeSkip = 1
isam = gtsam.ISAM2(parameters)

# Create a Factor Graph and Values to hold the new data
Expand Down
2 changes: 1 addition & 1 deletion python/gtsam/utils/visual_isam.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ def initialize(data, truth, options):
# Initialize iSAM
params = gtsam.ISAM2Params()
if options.alwaysRelinearize:
params.setRelinearizeSkip(1)
params.relinearizeSkip = 1
isam = gtsam.ISAM2(params=params)

# Add constraints/priors
Expand Down

0 comments on commit 65d72ab

Please sign in to comment.