|
Formula Student Autonomous Systems
The code for the main driverless system
|
Sliding Window Levenberg-Marquardt optimizer for graph SLAM. More...
#include <sliding_window_levenberg_optimizer.hpp>


Public Member Functions | |
| SlidingWindowLevenbergOptimizer (const SLAMParameters ¶ms) | |
| ~SlidingWindowLevenbergOptimizer () override=default | |
| std::shared_ptr< BaseOptimizer > | clone () const override |
| Clone the optimizer. | |
| gtsam::Values | optimize (gtsam::NonlinearFactorGraph &factor_graph, gtsam::Values &graph_values, unsigned int pose_num, unsigned int landmark_num) override |
| Optimize the graph. | |
Public Member Functions inherited from BaseOptimizer | |
| BaseOptimizer (const SLAMParameters ¶ms) | |
| BaseOptimizer (const BaseOptimizer &other) | |
| BaseOptimizer & | operator= (const BaseOptimizer &other) |
| virtual | ~BaseOptimizer ()=default |
Additional Inherited Members | |
Protected Attributes inherited from BaseOptimizer | |
| const SLAMParameters & | _params_ |
Sliding Window Levenberg-Marquardt optimizer for graph SLAM.
This class implements the sliding window Levenberg-Marquardt optimizer for graph SLAM It uses the GTSAM Levenberg-Marquardt implementation to optimize the factor graph within a sliding window of poses
Definition at line 13 of file sliding_window_levenberg_optimizer.hpp.
| SlidingWindowLevenbergOptimizer::SlidingWindowLevenbergOptimizer | ( | const SLAMParameters & | params | ) |
Definition at line 15 of file sliding_window_levenberg_optimizer.cpp.
|
overridedefault |
|
overridevirtual |
Clone the optimizer.
This method is used to create a copy of the optimizer It is useful for polymorphic classes that use pointers to base class
Implements BaseOptimizer.
Definition at line 11 of file sliding_window_levenberg_optimizer.cpp.
|
overridevirtual |
Optimize the graph.
This method is used to run the optimization on the graph It also updates the pose and the graph values accordingly afterwards It may change the factor graph
| factor_graph | The factor graph to optimize |
| graph_values | The values to optimize |
| pose_num | The number of poses in the graph |
| landmark_num | The number of landmarks in the graph |
Implements BaseOptimizer.
Definition at line 18 of file sliding_window_levenberg_optimizer.cpp.