Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
BaseOptimizer Class Referenceabstract

Base class for graph optimizers. More...

#include <base_optimizer.hpp>

Inheritance diagram for BaseOptimizer:
Inheritance graph
Collaboration diagram for BaseOptimizer:
Collaboration graph

Public Member Functions

 BaseOptimizer (const SLAMParameters &params)
 
 BaseOptimizer (const BaseOptimizer &other)
 
BaseOptimizeroperator= (const BaseOptimizer &other)
 
virtual std::shared_ptr< BaseOptimizerclone () 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_
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ BaseOptimizer() [1/2]

BaseOptimizer::BaseOptimizer ( const SLAMParameters params)
inlineexplicit

Definition at line 18 of file base_optimizer.hpp.

◆ BaseOptimizer() [2/2]

BaseOptimizer::BaseOptimizer ( const BaseOptimizer other)
inline

Definition at line 19 of file base_optimizer.hpp.

◆ ~BaseOptimizer()

virtual BaseOptimizer::~BaseOptimizer ( )
virtualdefault

Member Function Documentation

◆ clone()

virtual std::shared_ptr< BaseOptimizer > BaseOptimizer::clone ( ) const
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

Returns
A shared pointer to the cloned optimizer

Implemented in ISAM2Optimizer, NormalLevenbergOptimizer, and SlidingWindowLevenbergOptimizer.

◆ operator=()

BaseOptimizer & BaseOptimizer::operator= ( const BaseOptimizer other)
inline

Definition at line 20 of file base_optimizer.hpp.

Here is the caller graph for this function:

◆ optimize()

virtual gtsam::Values BaseOptimizer::optimize ( gtsam::NonlinearFactorGraph &  factor_graph,
gtsam::Values &  graph_values,
unsigned int  pose_num,
unsigned int  landmark_num 
)
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

Parameters
factor_graphThe factor graph to optimize
graph_valuesThe values to optimize
pose_numThe number of poses in the graph
landmark_numThe number of landmarks in the graph
Returns
The optimized values

Implemented in ISAM2Optimizer, NormalLevenbergOptimizer, and SlidingWindowLevenbergOptimizer.

Member Data Documentation

◆ _params_

const SLAMParameters& BaseOptimizer::_params_
protected

Definition at line 15 of file base_optimizer.hpp.


The documentation for this class was generated from the following file: