fixed initialization list warnings
parent
a6fd5ff9e2
commit
0b11a02183
|
@ -43,7 +43,7 @@ namespace gtsam {
|
|||
double absDecrease_; /* threshold for the absolute decrease per iteration */
|
||||
double relDecrease_; /* threshold for the relative decrease per iteration */
|
||||
double sumError_; /* threshold for the sum of error */
|
||||
int maxIterations_ ;
|
||||
size_t maxIterations_ ;
|
||||
double lambda_ ;
|
||||
double lambdaFactor_ ;
|
||||
verbosityLevel verbosity_;
|
||||
|
|
|
@ -37,8 +37,8 @@ namespace gtsam {
|
|||
template<class G, class C, class L, class S, class W>
|
||||
NonlinearOptimizer<G, C, L, S, W>::NonlinearOptimizer(shared_graph graph,
|
||||
shared_values values, shared_ordering ordering, shared_parameters parameters) :
|
||||
graph_(graph), values_(values), iterations_(0), error_(graph->error(*values)),
|
||||
ordering_(ordering), parameters_(parameters), dimensions_(new vector<size_t>(values->dims(*ordering))) {
|
||||
graph_(graph), values_(values), error_(graph->error(*values)), ordering_(ordering),
|
||||
parameters_(parameters), iterations_(0), dimensions_(new vector<size_t>(values->dims(*ordering))) {
|
||||
if (!graph) throw std::invalid_argument(
|
||||
"NonlinearOptimizer constructor: graph = NULL");
|
||||
if (!values) throw std::invalid_argument(
|
||||
|
@ -54,8 +54,8 @@ namespace gtsam {
|
|||
shared_ordering ordering,
|
||||
shared_solver solver,
|
||||
shared_parameters parameters):
|
||||
graph_(graph), values_(values), iterations_(0), error_(graph->error(*values)), ordering_(ordering), solver_(solver),
|
||||
parameters_(parameters), dimensions_(new vector<size_t>(values->dims(*ordering))) {
|
||||
graph_(graph), values_(values), error_(graph->error(*values)), ordering_(ordering), solver_(solver),
|
||||
parameters_(parameters), iterations_(0), dimensions_(new vector<size_t>(values->dims(*ordering))) {
|
||||
if (!graph) throw std::invalid_argument(
|
||||
"NonlinearOptimizer constructor: graph = NULL");
|
||||
if (!values) throw std::invalid_argument(
|
||||
|
|
|
@ -181,8 +181,9 @@ namespace gtsam {
|
|||
// ordering_(optimizer.ordering_), solver_(optimizer.solver_), lambda_(optimizer.lambda_), dimensions_(optimizer.dimensions_) {}
|
||||
|
||||
NonlinearOptimizer(const NonlinearOptimizer<G, T, L, GS> &optimizer) :
|
||||
graph_(optimizer.graph_), values_(optimizer.values_), iterations_(0), error_(optimizer.error_),
|
||||
ordering_(optimizer.ordering_), solver_(optimizer.solver_), parameters_(optimizer.parameters_), dimensions_(optimizer.dimensions_) {}
|
||||
graph_(optimizer.graph_), values_(optimizer.values_), error_(optimizer.error_),
|
||||
ordering_(optimizer.ordering_), solver_(optimizer.solver_),
|
||||
parameters_(optimizer.parameters_), iterations_(0), dimensions_(optimizer.dimensions_) {}
|
||||
|
||||
/**
|
||||
* Return current error
|
||||
|
|
Loading…
Reference in New Issue