From 65d72ab7a1c6590bef77f051e7b7c69a49ff43f7 Mon Sep 17 00:00:00 2001 From: senselessDev Date: Sat, 29 Jan 2022 22:35:24 +0100 Subject: [PATCH] adapt examples to new direct member access --- matlab/+gtsam/VisualISAMInitialize.m | 2 +- matlab/gtsam_examples/IMUKittiExampleGPS.m | 2 +- matlab/unstable_examples/+imuSimulator/IMUComparison.m | 2 +- matlab/unstable_examples/+imuSimulator/IMUComparison_with_cov.m | 2 +- matlab/unstable_examples/+imuSimulator/coriolisExample.m | 2 +- matlab/unstable_examples/IMUKittiExampleAdvanced.m | 2 +- matlab/unstable_examples/IMUKittiExampleVO.m | 2 +- python/gtsam/examples/IMUKittiExampleGPS.py | 2 +- python/gtsam/examples/Pose2ISAM2Example.py | 2 +- python/gtsam/examples/Pose3ISAM2Example.py | 2 +- python/gtsam/examples/VisualISAM2Example.py | 2 +- python/gtsam/utils/visual_isam.py | 2 +- 12 files changed, 12 insertions(+), 12 deletions(-) diff --git a/matlab/+gtsam/VisualISAMInitialize.m b/matlab/+gtsam/VisualISAMInitialize.m index 9b834e3e13..5605033452 100644 --- a/matlab/+gtsam/VisualISAMInitialize.m +++ b/matlab/+gtsam/VisualISAMInitialize.m @@ -7,7 +7,7 @@ %% Initialize iSAM params = gtsam.ISAM2Params; if options.alwaysRelinearize - params.setRelinearizeSkip(1); + params.relinearizeSkip = 1; end isam = ISAM2(params); diff --git a/matlab/gtsam_examples/IMUKittiExampleGPS.m b/matlab/gtsam_examples/IMUKittiExampleGPS.m index 530c3382c9..b350618e56 100755 --- a/matlab/gtsam_examples/IMUKittiExampleGPS.m +++ b/matlab/gtsam_examples/IMUKittiExampleGPS.m @@ -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; diff --git a/matlab/unstable_examples/+imuSimulator/IMUComparison.m b/matlab/unstable_examples/+imuSimulator/IMUComparison.m index ccc975d849..b753916c6e 100644 --- a/matlab/unstable_examples/+imuSimulator/IMUComparison.m +++ b/matlab/unstable_examples/+imuSimulator/IMUComparison.m @@ -46,7 +46,7 @@ %% Solver object isamParams = ISAM2Params; -isamParams.setRelinearizeSkip(1); +isamParams.relinearizeSkip = 1; isam = gtsam.ISAM2(isamParams); initialValues = Values; diff --git a/matlab/unstable_examples/+imuSimulator/IMUComparison_with_cov.m b/matlab/unstable_examples/+imuSimulator/IMUComparison_with_cov.m index 6adc8e9dc2..689d8a3f52 100644 --- a/matlab/unstable_examples/+imuSimulator/IMUComparison_with_cov.m +++ b/matlab/unstable_examples/+imuSimulator/IMUComparison_with_cov.m @@ -34,7 +34,7 @@ %% Solver object isamParams = ISAM2Params; -isamParams.setRelinearizeSkip(1); +isamParams.relinearizeSkip = 1; isam = gtsam.ISAM2(isamParams); sigma_init_x = 1.0; diff --git a/matlab/unstable_examples/+imuSimulator/coriolisExample.m b/matlab/unstable_examples/+imuSimulator/coriolisExample.m index 61dc78d968..dd276e2c1f 100644 --- a/matlab/unstable_examples/+imuSimulator/coriolisExample.m +++ b/matlab/unstable_examples/+imuSimulator/coriolisExample.m @@ -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; diff --git a/matlab/unstable_examples/IMUKittiExampleAdvanced.m b/matlab/unstable_examples/IMUKittiExampleAdvanced.m index cb13eacee2..b09764ec0e 100644 --- a/matlab/unstable_examples/IMUKittiExampleAdvanced.m +++ b/matlab/unstable_examples/IMUKittiExampleAdvanced.m @@ -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; diff --git a/matlab/unstable_examples/IMUKittiExampleVO.m b/matlab/unstable_examples/IMUKittiExampleVO.m index f35d365127..4183e439af 100644 --- a/matlab/unstable_examples/IMUKittiExampleVO.m +++ b/matlab/unstable_examples/IMUKittiExampleVO.m @@ -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; diff --git a/python/gtsam/examples/IMUKittiExampleGPS.py b/python/gtsam/examples/IMUKittiExampleGPS.py index 8b6b4fdf01..d00f633bae 100644 --- a/python/gtsam/examples/IMUKittiExampleGPS.py +++ b/python/gtsam/examples/IMUKittiExampleGPS.py @@ -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) diff --git a/python/gtsam/examples/Pose2ISAM2Example.py b/python/gtsam/examples/Pose2ISAM2Example.py index c70dbfa6f9..3a8de03174 100644 --- a/python/gtsam/examples/Pose2ISAM2Example.py +++ b/python/gtsam/examples/Pose2ISAM2Example.py @@ -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. diff --git a/python/gtsam/examples/Pose3ISAM2Example.py b/python/gtsam/examples/Pose3ISAM2Example.py index 59b9fb2ac1..cb71813c5a 100644 --- a/python/gtsam/examples/Pose3ISAM2Example.py +++ b/python/gtsam/examples/Pose3ISAM2Example.py @@ -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. diff --git a/python/gtsam/examples/VisualISAM2Example.py b/python/gtsam/examples/VisualISAM2Example.py index bacf510ec7..4b480fab72 100644 --- a/python/gtsam/examples/VisualISAM2Example.py +++ b/python/gtsam/examples/VisualISAM2Example.py @@ -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 diff --git a/python/gtsam/utils/visual_isam.py b/python/gtsam/utils/visual_isam.py index a8fed4b23d..4ebd8accdd 100644 --- a/python/gtsam/utils/visual_isam.py +++ b/python/gtsam/utils/visual_isam.py @@ -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