Merge pull request #1053 from senselessDev/develop
commit
ad0d7e4b21
|
@ -300,18 +300,10 @@ struct GTSAM_EXPORT ISAM2Params {
|
|||
RelinearizationThreshold getRelinearizeThreshold() const {
|
||||
return relinearizeThreshold;
|
||||
}
|
||||
int getRelinearizeSkip() const { return relinearizeSkip; }
|
||||
bool isEnableRelinearization() const { return enableRelinearization; }
|
||||
bool isEvaluateNonlinearError() const { return evaluateNonlinearError; }
|
||||
std::string getFactorization() const {
|
||||
return factorizationTranslator(factorization);
|
||||
}
|
||||
bool isCacheLinearizedFactors() const { return cacheLinearizedFactors; }
|
||||
KeyFormatter getKeyFormatter() const { return keyFormatter; }
|
||||
bool isEnableDetailedResults() const { return enableDetailedResults; }
|
||||
bool isEnablePartialRelinearizationCheck() const {
|
||||
return enablePartialRelinearizationCheck;
|
||||
}
|
||||
|
||||
void setOptimizationParams(OptimizationParams optimizationParams) {
|
||||
this->optimizationParams = optimizationParams;
|
||||
|
@ -319,31 +311,12 @@ struct GTSAM_EXPORT ISAM2Params {
|
|||
void setRelinearizeThreshold(RelinearizationThreshold relinearizeThreshold) {
|
||||
this->relinearizeThreshold = relinearizeThreshold;
|
||||
}
|
||||
void setRelinearizeSkip(int relinearizeSkip) {
|
||||
this->relinearizeSkip = relinearizeSkip;
|
||||
}
|
||||
void setEnableRelinearization(bool enableRelinearization) {
|
||||
this->enableRelinearization = enableRelinearization;
|
||||
}
|
||||
void setEvaluateNonlinearError(bool evaluateNonlinearError) {
|
||||
this->evaluateNonlinearError = evaluateNonlinearError;
|
||||
}
|
||||
void setFactorization(const std::string& factorization) {
|
||||
this->factorization = factorizationTranslator(factorization);
|
||||
}
|
||||
void setCacheLinearizedFactors(bool cacheLinearizedFactors) {
|
||||
this->cacheLinearizedFactors = cacheLinearizedFactors;
|
||||
}
|
||||
void setKeyFormatter(KeyFormatter keyFormatter) {
|
||||
this->keyFormatter = keyFormatter;
|
||||
}
|
||||
void setEnableDetailedResults(bool enableDetailedResults) {
|
||||
this->enableDetailedResults = enableDetailedResults;
|
||||
}
|
||||
void setEnablePartialRelinearizationCheck(
|
||||
bool enablePartialRelinearizationCheck) {
|
||||
this->enablePartialRelinearizationCheck = enablePartialRelinearizationCheck;
|
||||
}
|
||||
|
||||
GaussianFactorGraph::Eliminate getEliminationFunction() const {
|
||||
return factorization == CHOLESKY
|
||||
|
|
|
@ -588,21 +588,19 @@ class ISAM2Params {
|
|||
void setOptimizationParams(const gtsam::ISAM2DoglegParams& dogleg_params);
|
||||
void setRelinearizeThreshold(double threshold);
|
||||
void setRelinearizeThreshold(const gtsam::ISAM2ThresholdMap& threshold_map);
|
||||
int getRelinearizeSkip() const;
|
||||
void setRelinearizeSkip(int relinearizeSkip);
|
||||
bool isEnableRelinearization() const;
|
||||
void setEnableRelinearization(bool enableRelinearization);
|
||||
bool isEvaluateNonlinearError() const;
|
||||
void setEvaluateNonlinearError(bool evaluateNonlinearError);
|
||||
string getFactorization() const;
|
||||
void setFactorization(string factorization);
|
||||
bool isCacheLinearizedFactors() const;
|
||||
void setCacheLinearizedFactors(bool cacheLinearizedFactors);
|
||||
bool isEnableDetailedResults() const;
|
||||
void setEnableDetailedResults(bool enableDetailedResults);
|
||||
bool isEnablePartialRelinearizationCheck() const;
|
||||
void setEnablePartialRelinearizationCheck(
|
||||
bool enablePartialRelinearizationCheck);
|
||||
|
||||
int relinearizeSkip;
|
||||
bool enableRelinearization;
|
||||
bool evaluateNonlinearError;
|
||||
bool cacheLinearizedFactors;
|
||||
bool enableDetailedResults;
|
||||
bool enablePartialRelinearizationCheck;
|
||||
bool findUnusedFactorSlots;
|
||||
|
||||
enum Factorization { CHOLESKY, QR };
|
||||
Factorization factorization;
|
||||
};
|
||||
|
||||
class ISAM2Clique {
|
||||
|
|
|
@ -566,7 +566,13 @@ virtual class FixedLagSmoother {
|
|||
gtsam::FixedLagSmootherKeyTimestampMap timestamps() const;
|
||||
double smootherLag() const;
|
||||
|
||||
gtsam::FixedLagSmootherResult update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::FixedLagSmootherKeyTimestampMap& timestamps);
|
||||
gtsam::FixedLagSmootherResult update(const gtsam::NonlinearFactorGraph &newFactors,
|
||||
const gtsam::Values &newTheta,
|
||||
const gtsam::FixedLagSmootherKeyTimestampMap ×tamps);
|
||||
gtsam::FixedLagSmootherResult update(const gtsam::NonlinearFactorGraph &newFactors,
|
||||
const gtsam::Values &newTheta,
|
||||
const gtsam::FixedLagSmootherKeyTimestampMap ×tamps,
|
||||
const gtsam::FactorIndices &factorsToRemove);
|
||||
gtsam::Values calculateEstimate() const;
|
||||
};
|
||||
|
||||
|
@ -576,6 +582,8 @@ virtual class BatchFixedLagSmoother : gtsam::FixedLagSmoother {
|
|||
BatchFixedLagSmoother(double smootherLag);
|
||||
BatchFixedLagSmoother(double smootherLag, const gtsam::LevenbergMarquardtParams& params);
|
||||
|
||||
void print(string s = "BatchFixedLagSmoother:\n") const;
|
||||
|
||||
gtsam::LevenbergMarquardtParams params() const;
|
||||
template <VALUE = {gtsam::Point2, gtsam::Rot2, gtsam::Pose2, gtsam::Point3,
|
||||
gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2,
|
||||
|
@ -589,7 +597,12 @@ virtual class IncrementalFixedLagSmoother : gtsam::FixedLagSmoother {
|
|||
IncrementalFixedLagSmoother(double smootherLag);
|
||||
IncrementalFixedLagSmoother(double smootherLag, const gtsam::ISAM2Params& params);
|
||||
|
||||
void print(string s = "IncrementalFixedLagSmoother:\n") const;
|
||||
|
||||
gtsam::ISAM2Params params() const;
|
||||
|
||||
gtsam::NonlinearFactorGraph getFactors() const;
|
||||
gtsam::ISAM2 getISAM2() const;
|
||||
};
|
||||
|
||||
#include <gtsam_unstable/nonlinear/ConcurrentFilteringAndSmoothing.h>
|
||||
|
|
|
@ -113,6 +113,9 @@ public:
|
|||
/// Get results of latest isam2 update
|
||||
const ISAM2Result& getISAM2Result() const{ return isamResult_; }
|
||||
|
||||
/// Get the iSAM2 object which is used for the inference internally
|
||||
const ISAM2& getISAM2() const { return isam_; }
|
||||
|
||||
protected:
|
||||
|
||||
/** Create default parameters */
|
||||
|
|
|
@ -7,7 +7,7 @@ import gtsam.*
|
|||
%% Initialize iSAM
|
||||
params = gtsam.ISAM2Params;
|
||||
if options.alwaysRelinearize
|
||||
params.setRelinearizeSkip(1);
|
||||
params.relinearizeSkip = 1;
|
||||
end
|
||||
isam = ISAM2(params);
|
||||
|
||||
|
|
|
@ -52,7 +52,7 @@ IMU_params.setOmegaCoriolis(w_coriolis);
|
|||
%% Solver object
|
||||
isamParams = ISAM2Params;
|
||||
isamParams.setFactorization('CHOLESKY');
|
||||
isamParams.setRelinearizeSkip(10);
|
||||
isamParams.relinearizeSkip = 10;
|
||||
isam = gtsam.ISAM2(isamParams);
|
||||
newFactors = NonlinearFactorGraph;
|
||||
newValues = Values;
|
||||
|
|
|
@ -46,7 +46,7 @@ posesIMUbody(1).R = poses(1).R;
|
|||
|
||||
%% Solver object
|
||||
isamParams = ISAM2Params;
|
||||
isamParams.setRelinearizeSkip(1);
|
||||
isamParams.relinearizeSkip = 1;
|
||||
isam = gtsam.ISAM2(isamParams);
|
||||
|
||||
initialValues = Values;
|
||||
|
|
|
@ -34,7 +34,7 @@ poses(1).R = currentPoseGlobal.rotation.matrix;
|
|||
|
||||
%% Solver object
|
||||
isamParams = ISAM2Params;
|
||||
isamParams.setRelinearizeSkip(1);
|
||||
isamParams.relinearizeSkip = 1;
|
||||
isam = gtsam.ISAM2(isamParams);
|
||||
|
||||
sigma_init_x = 1.0;
|
||||
|
|
|
@ -119,7 +119,7 @@ h = figure;
|
|||
% Solver object
|
||||
isamParams = ISAM2Params;
|
||||
isamParams.setFactorization('CHOLESKY');
|
||||
isamParams.setRelinearizeSkip(10);
|
||||
isamParams.relinearizeSkip = 10;
|
||||
isam = gtsam.ISAM2(isamParams);
|
||||
newFactors = NonlinearFactorGraph;
|
||||
newValues = Values;
|
||||
|
|
|
@ -82,7 +82,7 @@ w_coriolis = [0;0;0];
|
|||
%% Solver object
|
||||
isamParams = ISAM2Params;
|
||||
isamParams.setFactorization('QR');
|
||||
isamParams.setRelinearizeSkip(1);
|
||||
isamParams.relinearizeSkip = 1;
|
||||
isam = gtsam.ISAM2(isamParams);
|
||||
newFactors = NonlinearFactorGraph;
|
||||
newValues = Values;
|
||||
|
|
|
@ -58,7 +58,7 @@ w_coriolis = [0;0;0];
|
|||
%% Solver object
|
||||
isamParams = ISAM2Params;
|
||||
isamParams.setFactorization('CHOLESKY');
|
||||
isamParams.setRelinearizeSkip(10);
|
||||
isamParams.relinearizeSkip = 10;
|
||||
isam = gtsam.ISAM2(isamParams);
|
||||
newFactors = NonlinearFactorGraph;
|
||||
newValues = Values;
|
||||
|
|
|
@ -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)
|
||||
|
||||
|
|
|
@ -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.
|
||||
|
|
|
@ -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.
|
||||
|
|
|
@ -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
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue