34 typedef boost::shared_ptr<ConcurrentBatchFilter>
shared_ptr;
53 Result() : iterations(0), lambdas(0), nonlinearVariables(0), linearVariables(0), error(0) {};
107 template<
class VALUE>
110 return theta_.at<VALUE>(
key).retract(delta);
127 const boost::optional<
FastList<Key> >& keysToMove = boost::none,
const boost::optional< std::vector<size_t> >& removeFactorIndices = boost::none);
133 void presync()
override;
165 void postsync()
override;
200 void removeFactors(
const std::vector<size_t>& slots);
203 void reorder(
const boost::optional<
FastList<Key> >& keysToMove = boost::none);
238 template<
class Container>
244 template<
class Container>
246 std::cout << indent << title;
248 std::cout <<
" " << keyFormatter(
key);
250 std::cout << std::endl;
void print(const Matrix &A, const string &s, ostream &stream)
const NonlinearFactorGraph & getFactors() const
~ConcurrentBatchFilter() override
ConcurrentBatchFilter(const LevenbergMarquardtParams ¶meters=LevenbergMarquardtParams())
NonlinearFactorGraph smootherSummarization_
The smoother summarization on the old separator sent by the smoother during the last synchronization...
ConcurrentFilter Base
typedef for base class
double error
The final factor graph error.
std::vector< size_t > newFactorsIndices
static enum @843 ordering
size_t getIterations() const
Getter methods.
Values separatorValues_
The linearization points of the separator variables. These should not be updated during optimization...
GaussianFactorGraph factors(list_of(factor1)(factor2)(factor3))
Values retract(const VectorValues &delta) const
std::queue< size_t > availableSlots_
The set of available factor graph slots caused by deleting factors.
size_t lambdas
The number of different L-M lambda factors that were tried during optimization.
static const KeyFormatter DefaultKeyFormatter
size_t getNonlinearVariables() const
static void PrintKeys(const Container &keys, const std::string &indent, const std::string &title, const KeyFormatter &keyFormatter=DefaultKeyFormatter)
Implementation of PrintKeys.
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
size_t getLambdas() const
boost::shared_ptr< This > shared_ptr
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
NonlinearFactorGraph smootherShortcut_
A set of conditional factors from the old separator to the current separator (recursively calculated ...
size_t linearVariables
The number of variables that must keep a constant linearization point.
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
boost::shared_ptr< ConcurrentBatchFilter > shared_ptr
size_t nonlinearVariables
The number of variables that can be relinearized.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
LevenbergMarquardtParams parameters_
LM parameters.
Values theta_
Current linearization point of all variables in the filter.
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
static ConjugateGradientParameters parameters
size_t iterations
The number of optimizer iterations performed.
const VectorValues & getDelta() const
std::vector< float > Values
NonlinearFactorGraph smootherFactors_
A temporary holding place for the set of full nonlinear factors being sent to the smoother...
const Ordering & getOrdering() const
size_t getLinearVariables() const
void synchronize(ConcurrentFilter &filter, ConcurrentSmoother &smoother)
VectorValues delta_
The current set of linear deltas from the linearization point.
Ordering ordering_
The current ordering used to calculate the linear deltas.
NonlinearFactorGraph factors_
The set of all factors currently in the filter.
NonlinearFactorGraph filterSummarization_
A temporary holding place for calculated filter summarization factors to be sent to the smoother...
ConcurrentBatchFilter::Result ConcurrentBatchFilterResult
Typedef for Matlab wrapping.
std::vector< size_t > separatorSummarizationSlots_
The slots in factor graph that correspond to the current smoother summarization on the current separa...
Base classes for the 'filter' and 'smoother' portion of the Concurrent Filtering and Smoothing archit...
VALUE calculateEstimate(Key key) const
std::uint64_t Key
Integer nonlinear key type.
const Values & getLinearizationPoint() const
Values calculateEstimate() const
Values smootherValues_
A temporary holding place for the linearization points of all keys being sent to the smoother...