Returning Values reference from EasyFactorGraph::optimize caused segfault
parent
c67cd8098d
commit
26dcb4a992
|
|
@ -33,14 +33,14 @@ namespace gtsam {
|
|||
return LevenbergMarquardtOptimizer((*this), initialEstimate, p);
|
||||
}
|
||||
|
||||
const Values& EasyFactorGraph::optimize(const Values& initialEstimate,
|
||||
Values EasyFactorGraph::optimize(const Values& initialEstimate,
|
||||
size_t verbosity) const {
|
||||
LevenbergMarquardtParams p;
|
||||
p.verbosity = (NonlinearOptimizerParams::Verbosity) verbosity;
|
||||
return optimizer(initialEstimate, p).optimizeSafely();
|
||||
}
|
||||
|
||||
const Values& EasyFactorGraph::optimizeSPCG(const Values& initialEstimate,
|
||||
Values EasyFactorGraph::optimizeSPCG(const Values& initialEstimate,
|
||||
size_t verbosity) const {
|
||||
LevenbergMarquardtParams p;
|
||||
p.verbosity = (NonlinearOptimizerParams::Verbosity) verbosity;
|
||||
|
|
|
|||
|
|
@ -49,14 +49,14 @@ namespace gtsam {
|
|||
* @param initialEstimate initial estimate of all variables in the graph
|
||||
* @param verbosity unsigned specifying verbosity level
|
||||
*/
|
||||
const Values& optimize(const Values& initialEstimate, size_t verbosity = 0) const;
|
||||
Values optimize(const Values& initialEstimate, size_t verbosity = 0) const;
|
||||
|
||||
/**
|
||||
* Safely optimize using subgraph preconditioning
|
||||
* @param initialEstimate initial estimate of all variables in the graph
|
||||
* @param verbosity unsigned specifying verbosity level
|
||||
*/
|
||||
const Values& optimizeSPCG(const Values& initialEstimate, size_t verbosity = 0) const;
|
||||
Values optimizeSPCG(const Values& initialEstimate, size_t verbosity = 0) const;
|
||||
|
||||
/**
|
||||
* Return a Marginals object, so you can query marginals
|
||||
|
|
|
|||
Loading…
Reference in New Issue