|
Formula Student Autonomous Systems
The code for the main driverless system
|
Interface for SLAM solvers. More...
#include <slam_solver.hpp>


Public Member Functions | |
| SLAMSolver (const SLAMParameters ¶ms, std::shared_ptr< DataAssociationModel > data_association, std::shared_ptr< V2PMotionModel > motion_model, std::shared_ptr< LandmarkFilter > landmark_filter, std::shared_ptr< std::vector< double > > execution_times, std::shared_ptr< LoopClosure > loop_closure) | |
| Construct a new SLAMSolver object. | |
| virtual | ~SLAMSolver ()=default |
| virtual void | add_observations (const std::vector< common_lib::structures::Cone > &cones, rclcpp::Time cones_timestamp)=0 |
| Add observations to the solver. | |
| virtual void | add_velocities (const common_lib::structures::Velocities &velocities)=0 |
| Process new velocity data. | |
| virtual void | load_initial_state (const Eigen::VectorXd &map, const Eigen::Vector3d &pose)=0 |
| Loads a previously saved map and pose into the solver. | |
| virtual std::vector< common_lib::structures::Cone > | get_map_estimate ()=0 |
| Get the map estimate object. | |
| virtual common_lib::structures::Pose | get_pose_estimate ()=0 |
| Get the pose estimate object. | |
| virtual Eigen::MatrixXd | get_covariance ()=0 |
| Get covariance matrix. | |
| virtual int | get_lap_counter ()=0 |
| Get the lap counter. | |
| virtual Eigen::VectorXi | get_associations () const =0 |
| virtual Eigen::VectorXd | get_observations_global () const =0 |
| virtual Eigen::VectorXd | get_map_coordinates () const =0 |
| void | set_mission (common_lib::competition_logic::Mission mission) |
| Set the mission. | |
Protected Attributes | |
| SLAMParameters | _params_ |
| std::shared_ptr< DataAssociationModel > | _data_association_ |
| std::shared_ptr< V2PMotionModel > | _motion_model_ |
| std::shared_ptr< LandmarkFilter > | _landmark_filter_ |
| common_lib::competition_logic::Mission | _mission_ = common_lib::competition_logic::Mission::NONE |
| std::shared_ptr< std::vector< double > > | _execution_times_ |
| std::shared_ptr< LoopClosure > | _loop_closure_ |
| rclcpp::Time | _last_pose_update_ = rclcpp::Time(0) |
| rclcpp::Time | _last_observation_update_ = rclcpp::Time(0) |
| bool | _received_first_velocities_ |
| int | lap_counter_ = 0 |
Interface for SLAM solvers.
This class defines the interface for SLAM solvers like EKF or GTSAM
Definition at line 22 of file slam_solver.hpp.
| SLAMSolver::SLAMSolver | ( | const SLAMParameters & | params, |
| std::shared_ptr< DataAssociationModel > | data_association, | ||
| std::shared_ptr< V2PMotionModel > | motion_model, | ||
| std::shared_ptr< LandmarkFilter > | landmark_filter, | ||
| std::shared_ptr< std::vector< double > > | execution_times, | ||
| std::shared_ptr< LoopClosure > | loop_closure | ||
| ) |
Construct a new SLAMSolver object.
| params | Parameters for the SLAM solver |
| data_association | Data association module |
| motion_model | Motion model |
| execution_times | Timekeeping array |
| loop_closure | Loop closure model |
Definition at line 3 of file slam_solver.cpp.
|
virtualdefault |
|
pure virtual |
Add observations to the solver.
| cones | Positions of the observations |
Implemented in GraphSLAMSolver, and EKFSLAMSolver.
|
pure virtual |
Process new velocity data.
| velocities | Velocities data |
Implemented in EKFSLAMSolver, and GraphSLAMSolver.
|
pure virtual |
Implemented in EKFSLAMSolver, and GraphSLAMSolver.
|
pure virtual |
|
pure virtual |
|
pure virtual |
Implemented in EKFSLAMSolver, and GraphSLAMSolver.
|
pure virtual |
Get the map estimate object.
Implemented in EKFSLAMSolver, and GraphSLAMSolver.
|
pure virtual |
Implemented in EKFSLAMSolver, and GraphSLAMSolver.
|
pure virtual |
Get the pose estimate object.
Implemented in EKFSLAMSolver, and GraphSLAMSolver.
|
pure virtual |
Loads a previously saved map and pose into the solver.
| map | coordinates of the landmarks in the form of [x1, y1, x2, y2, ...] in the global frame |
| pose | initial pose of the robot in the form of [x, y, theta] in the global frame |
Implemented in EKFSLAMSolver, and GraphSLAMSolver.

| void SLAMSolver::set_mission | ( | common_lib::competition_logic::Mission | mission | ) |
Set the mission.
| mission |
Definition at line 16 of file slam_solver.cpp.

|
protected |
Definition at line 25 of file slam_solver.hpp.
|
protected |
Definition at line 30 of file slam_solver.hpp.
|
protected |
Definition at line 27 of file slam_solver.hpp.
|
protected |
Definition at line 35 of file slam_solver.hpp.
|
protected |
Definition at line 34 of file slam_solver.hpp.
|
protected |
Definition at line 32 of file slam_solver.hpp.
|
protected |
Definition at line 28 of file slam_solver.hpp.
|
protected |
Definition at line 26 of file slam_solver.hpp.
|
protected |
Definition at line 24 of file slam_solver.hpp.
|
protected |
Definition at line 37 of file slam_solver.hpp.
|
protected |
Definition at line 40 of file slam_solver.hpp.