![]() |
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
#include <sliding_window_graph_optimizer.h>

Public Member Functions | |
| SlidingWindowGraphOptimizer (const SlidingWindowGraphOptimizerParams ¶ms, std::unique_ptr< optimizers::Optimizer > optimizer) | |
| virtual | ~SlidingWindowGraphOptimizer ()=default |
| SlidingWindowGraphOptimizer () | |
| void | AddSlidingWindowNodeAdder (std::shared_ptr< node_adders::SlidingWindowNodeAdder > sliding_window_node_adder) |
| bool | Update () |
| const localization_common::Timer & | update_timer () const |
| double | Duration () const |
Public Member Functions inherited from graph_optimizer::GraphOptimizer | |
| GraphOptimizer (const GraphOptimizerParams ¶ms, std::unique_ptr< optimizers::Optimizer > optimizer) | |
| GraphOptimizer () | |
| virtual | ~GraphOptimizer ()=default |
| void | AddNodeAdder (std::shared_ptr< node_adders::NodeAdder > node_adder) |
| void | AddFactorAdder (std::shared_ptr< factor_adders::FactorAdder > factor_adder) |
| int | AddFactors (const localization_common::Time start_time, const localization_common::Time end_time) |
| int | AddFactors (const std::pair< localization_common::Time, localization_common::Time > &start_and_end_time) |
| bool | Optimize () |
| boost::optional< gtsam::Matrix > | Covariance (const gtsam::Key &key) const |
| boost::optional< gtsam::Matrix > | Covariance (const gtsam::Key &key_a, const gtsam::Key &key_b) const |
| const gtsam::NonlinearFactorGraph & | factors () const |
| gtsam::NonlinearFactorGraph & | factors () |
| template<typename FactorType > | |
| std::vector< boost::shared_ptr< const FactorType > > | Factors () const |
| int | num_factors () const |
| template<typename FactorType > | |
| int | NumFactors () const |
| int | num_values () const |
| const GraphOptimizerParams & | params () const |
| std::shared_ptr< nodes::Values > | values () |
| const gtsam::Values & | gtsam_values () const |
| localization_common::StatsLogger & | stats_logger () |
| const localization_common::Timer & | optimization_timer () const |
| const localization_common::Averager & | optimization_iterations_averager () const |
| double | TotalGraphError () const |
| virtual bool | ValidGraph () const |
| virtual void | Print () const |
| void | SaveGraphDotFile (const std::string &output_path="graph.dot") const |
| boost::optional< const gtsam::Marginals & > | marginals () const |
Friends | |
| class | boost::serialization::access |
| sliding_window_graph_optimizer::SlidingWindowGraphOptimizer::SlidingWindowGraphOptimizer | ( | const SlidingWindowGraphOptimizerParams & | params, |
| std::unique_ptr< optimizers::Optimizer > | optimizer | ||
| ) |
|
virtualdefault |
|
inline |
| void sliding_window_graph_optimizer::SlidingWindowGraphOptimizer::AddSlidingWindowNodeAdder | ( | std::shared_ptr< node_adders::SlidingWindowNodeAdder > | sliding_window_node_adder | ) |
| double sliding_window_graph_optimizer::SlidingWindowGraphOptimizer::Duration | ( | ) | const |
| bool sliding_window_graph_optimizer::SlidingWindowGraphOptimizer::Update | ( | ) |
| const localization_common::Timer & sliding_window_graph_optimizer::SlidingWindowGraphOptimizer::update_timer | ( | ) | const |
|
friend |