Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
map.hpp
Go to the documentation of this file.
1#pragma once
2
3#include <map>
4#include <memory>
5#include <string>
6
11
12/*
13 * Map of optimizers, with the key being the type of the optimizer and the value being a lambda
14 * function that returns a shared pointer to the corresponding optimizer
15 */
16const std::map<std::string, std::function<std::shared_ptr<BaseOptimizer>(const SLAMParameters&)>,
17 std::less<>>
19 {"normal_levenberg",
20 [](const SLAMParameters& params) -> std::shared_ptr<BaseOptimizer> {
21 return std::make_shared<NormalLevenbergOptimizer>(params);
22 }},
23 {"sliding_window_levenberg",
24 [](const SLAMParameters& params) -> std::shared_ptr<BaseOptimizer> {
25 return std::make_shared<SlidingWindowLevenbergOptimizer>(params);
26 }},
27 {"isam2",
28 [](const SLAMParameters& params) -> std::shared_ptr<BaseOptimizer> {
29 return std::make_shared<ISAM2Optimizer>(params);
30 }},
31};
const std::map< std::string, std::function< std::shared_ptr< BaseOptimizer >(const SLAMParameters &)>, std::less<> > graph_slam_optimizer_constructors_map
Definition map.hpp:18
Parameters for the SLAM node.