|
Formula Student Autonomous Systems
The code for the main driverless system
|
Base class for graph optimizers. More...
#include <base_optimizer.hpp>


Public Member Functions | |
| BaseOptimizer (const SLAMParameters ¶ms) | |
| BaseOptimizer (const BaseOptimizer &other) | |
| BaseOptimizer & | operator= (const BaseOptimizer &other) |
| virtual std::shared_ptr< BaseOptimizer > | clone () const =0 |
| Clone the optimizer. | |
| virtual | ~BaseOptimizer ()=default |
| virtual gtsam::Values | optimize (gtsam::NonlinearFactorGraph &factor_graph, gtsam::Values &graph_values, unsigned int pose_num, unsigned int landmark_num)=0 |
| Optimize the graph. | |
Protected Attributes | |
| const SLAMParameters & | _params_ |
Base class for graph optimizers.
This class defines the interface for graph optimizers It is used to optimize the factor graph and update the pose and graph values accordingly
Definition at line 13 of file base_optimizer.hpp.
|
inlineexplicit |
Definition at line 18 of file base_optimizer.hpp.
|
inline |
Definition at line 19 of file base_optimizer.hpp.
|
virtualdefault |
|
pure virtual |
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
Implemented in ISAM2Optimizer, NormalLevenbergOptimizer, and SlidingWindowLevenbergOptimizer.
|
inline |
|
pure virtual |
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 |
Implemented in ISAM2Optimizer, NormalLevenbergOptimizer, and SlidingWindowLevenbergOptimizer.
|
protected |
Definition at line 15 of file base_optimizer.hpp.