Go to the documentation of this file.
34 typedef std::shared_ptr<ConcurrentBatchFilter>
shared_ptr;
53 Result() : iterations(0), lambdas(0), nonlinearVariables(0), linearVariables(0),
error(0) {}
107 template<
class VALUE>
127 const std::optional<
FastList<Key> >& keysToMove = {},
const std::optional< std::vector<size_t> >& removeFactorIndices = {});
133 void presync()
override;
142 void getSummarizedFactors(NonlinearFactorGraph& filterSummarization,
Values& filterSummarizationValues)
override;
152 void getSmootherFactors(NonlinearFactorGraph& smootherFactors,
Values& smootherValues)
override;
159 void synchronize(
const NonlinearFactorGraph& smootherSummarization,
const Values& smootherSummarizationValues)
override;
165 void postsync()
override;
200 void removeFactors(
const std::vector<size_t>& slots);
203 void reorder(
const std::optional<
FastList<Key> >& keysToMove = {});
238 template<
class Container>
244 template<
class Container>
246 std::cout << indent << title;
248 std::cout <<
" " << keyFormatter(
key);
250 std::cout << std::endl;
std::shared_ptr< This > shared_ptr
std::vector< size_t > newFactorsIndices
Values separatorValues_
The linearization points of the separator variables. These should not be updated during optimization.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
size_t getLinearVariables() const
ConcurrentFilter Base
typedef for base class
ConcurrentBatchFilter(const LevenbergMarquardtParams ¶meters=LevenbergMarquardtParams())
void synchronize(ConcurrentFilter &filter, ConcurrentSmoother &smoother)
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
const GaussianFactorGraph factors
const NonlinearFactorGraph & getFactors() const
NonlinearFactorGraph factors_
The set of all factors currently in the filter.
def retract(a, np.ndarray xi)
NonlinearFactorGraph smootherFactors_
A temporary holding place for the set of full nonlinear factors being sent to the smoother.
static void PrintKeys(const Container &keys, const std::string &indent, const std::string &title, const KeyFormatter &keyFormatter=DefaultKeyFormatter)
Implementation of PrintKeys.
NonlinearFactorGraph smootherSummarization_
The smoother summarization on the old separator sent by the smoother during the last synchronization.
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
LevenbergMarquardtParams parameters_
LM parameters.
Values smootherValues_
A temporary holding place for the linearization points of all keys being sent to the smoother.
void print(const Matrix &A, const string &s, ostream &stream)
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.
ConcurrentBatchFilter::Result ConcurrentBatchFilterResult
Typedef for Matlab wrapping.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
static ConjugateGradientParameters parameters
std::shared_ptr< This > shared_ptr
shared_ptr to this class
size_t nonlinearVariables
The number of variables that can be relinearized.
size_t getNonlinearVariables() const
VALUE calculateEstimate(Key key) const
size_t getLambdas() const
const Ordering & getOrdering() const
static enum @1096 ordering
size_t getIterations() const
Getter methods.
const gtsam::Symbol key('X', 0)
size_t iterations
The number of optimizer iterations performed.
std::vector< float > Values
size_t linearVariables
The number of variables that must keep a constant linearization point.
Base classes for the 'filter' and 'smoother' portion of the Concurrent Filtering and Smoothing archit...
Values calculateEstimate() const
std::shared_ptr< ConcurrentBatchFilter > shared_ptr
VectorValues delta_
The current set of linear deltas from the linearization point.
Ordering ordering_
The current ordering used to calculate the linear deltas.
Values theta_
Current linearization point of all variables in the filter.
const VectorValues & getDelta() const
std::uint64_t Key
Integer nonlinear key type.
NonlinearFactorGraph filterSummarization_
A temporary holding place for calculated filter summarization factors to be sent to the smoother.
double error
The final factor graph error.
NonlinearFactorGraph smootherShortcut_
A set of conditional factors from the old separator to the current separator (recursively calculated ...
std::vector< size_t > separatorSummarizationSlots_
The slots in factor graph that correspond to the current smoother summarization on the current separa...
const Values & getLinearizationPoint() const
gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:32:09