Removed references to the old nonlinear optimizer parameters from Matlab
parent
f3ed18dfdc
commit
3dc3f93145
|
@ -55,10 +55,10 @@ initialEstimate.insertPose(x3, gtsamPose2(4.1, 0.1, 0.1));
|
||||||
initialEstimate.print('initial estimate');
|
initialEstimate.print('initial estimate');
|
||||||
|
|
||||||
%% set up solver, choose ordering and optimize
|
%% set up solver, choose ordering and optimize
|
||||||
params = gtsamNonlinearOptimizationParameters_newDecreaseThresholds(1e-15, 1e-15);
|
%params = gtsamNonlinearOptimizationParameters_newDecreaseThresholds(1e-15, 1e-15);
|
||||||
|
%
|
||||||
ord = graph.orderingCOLAMD(initialEstimate);
|
%ord = graph.orderingCOLAMD(initialEstimate);
|
||||||
|
%
|
||||||
%result = pose2SLAMOptimizer(graph,initialEstimate,ord,params);
|
%result = pose2SLAMOptimizer(graph,initialEstimate,ord,params);
|
||||||
%result.print('final result');
|
%result.print('final result');
|
||||||
|
|
||||||
|
|
21
gtsam.h
21
gtsam.h
|
@ -410,15 +410,6 @@ class Ordering {
|
||||||
void push_back(size_t key);
|
void push_back(size_t key);
|
||||||
};
|
};
|
||||||
|
|
||||||
class NonlinearOptimizationParameters {
|
|
||||||
NonlinearOptimizationParameters(double absDecrease, double relDecrease,
|
|
||||||
double sumError, int iIters, double lambda, double lambdaFactor);
|
|
||||||
void print(string s) const;
|
|
||||||
static gtsam::NonlinearOptimizationParameters* newDecreaseThresholds(double absDecrease,
|
|
||||||
double relDecrease);
|
|
||||||
};
|
|
||||||
|
|
||||||
|
|
||||||
}///\namespace gtsam
|
}///\namespace gtsam
|
||||||
|
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
|
@ -464,12 +455,6 @@ class Odometry {
|
||||||
gtsam::GaussianFactor* linearize(const planarSLAM::Values& center, const gtsam::Ordering& ordering) const;
|
gtsam::GaussianFactor* linearize(const planarSLAM::Values& center, const gtsam::Ordering& ordering) const;
|
||||||
};
|
};
|
||||||
|
|
||||||
class Optimizer {
|
|
||||||
Optimizer(planarSLAM::Graph* graph, planarSLAM::Values* values,
|
|
||||||
gtsam::Ordering* ordering, gtsam::NonlinearOptimizationParameters* parameters);
|
|
||||||
void print(string s) const;
|
|
||||||
};
|
|
||||||
|
|
||||||
}///\namespace planarSLAM
|
}///\namespace planarSLAM
|
||||||
|
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
|
@ -502,12 +487,6 @@ class Graph {
|
||||||
pose2SLAM::Values optimize(const pose2SLAM::Values& initialEstimate);
|
pose2SLAM::Values optimize(const pose2SLAM::Values& initialEstimate);
|
||||||
};
|
};
|
||||||
|
|
||||||
class Optimizer {
|
|
||||||
Optimizer(pose2SLAM::Graph* graph, pose2SLAM::Values* values,
|
|
||||||
gtsam::Ordering* ordering, gtsam::NonlinearOptimizationParameters* parameters);
|
|
||||||
void print(string s) const;
|
|
||||||
};
|
|
||||||
|
|
||||||
}///\namespace pose2SLAM
|
}///\namespace pose2SLAM
|
||||||
|
|
||||||
//*************************************************************************
|
//*************************************************************************
|
||||||
|
|
Loading…
Reference in New Issue