34 typedef boost::shared_ptr<ConcurrentBatchSmoother>
shared_ptr;
46 Result() : iterations(0), lambdas(0), nonlinearVariables(0), linearVariables(0), error(0) {};
100 template<
class VALUE>
103 return theta_.at<VALUE>(
key).retract(delta);
121 const boost::optional< std::vector<size_t> >& removeFactorIndices = boost::none);
127 void presync()
override;
153 void postsync()
override;
183 void removeFactors(
const std::vector<size_t>& slots);
192 void updateSmootherSummarization();
void print(const Matrix &A, const string &s, ostream &stream)
NonlinearFactorGraph smootherSummarization_
A temporary holding place for calculated smoother summarization.
~ConcurrentBatchSmoother() override
VALUE calculateEstimate(Key key) const
size_t nonlinearVariables
The number of variables that can be relinearized.
size_t lambdas
The number of different L-M lambda factors that were tried during optimization.
Ordering ordering_
The current ordering used to calculate the linear deltas.
Values separatorValues_
The linearization points of the separator variables. These should not be updated during optimization...
GaussianFactorGraph factors(list_of(factor1)(factor2)(factor3))
VectorValues delta_
The current set of linear deltas from the linearization point.
Values retract(const VectorValues &delta) const
ConcurrentBatchSmoother(const LevenbergMarquardtParams ¶meters=LevenbergMarquardtParams())
static const KeyFormatter DefaultKeyFormatter
const Values & getLinearizationPoint() const
size_t getIterations() const
Getter methods.
const VectorValues & getDelta() const
ConcurrentBatchSmoother::Result ConcurrentBatchSmootherResult
Typedef for Matlab wrapping.
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
ConcurrentSmoother Base
typedef for base class
size_t iterations
The number of optimizer iterations performed.
double error
The final factor graph error.
boost::shared_ptr< This > shared_ptr
size_t getLambdas() const
VariableIndex variableIndex_
The current variable index, which allows efficient factor lookup by variable.
size_t getLinearVariables() const
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
const Ordering & getOrdering() const
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Values calculateEstimate() const
LevenbergMarquardtParams parameters_
LM parameters.
Values theta_
Current linearization point of all variables in the smoother.
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
size_t linearVariables
The number of variables that must keep a constant linearization point.
static ConjugateGradientParameters parameters
std::vector< float > Values
std::vector< size_t > filterSummarizationSlots_
The slots in factor graph that correspond to the current filter summarization factors.
NonlinearFactorGraph factors_
The set of all factors currently in the smoother.
void synchronize(ConcurrentFilter &filter, ConcurrentSmoother &smoother)
size_t getNonlinearVariables() const
const NonlinearFactorGraph & getFactors() const
Base classes for the 'filter' and 'smoother' portion of the Concurrent Filtering and Smoothing archit...
std::queue< size_t > availableSlots_
The set of available factor graph slots caused by deleting factors.
std::uint64_t Key
Integer nonlinear key type.
boost::shared_ptr< ConcurrentBatchSmoother > shared_ptr