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

Interface for SLAM solvers. More...

#include <slam_solver.hpp>

Inheritance diagram for SLAMSolver:
Inheritance graph
Collaboration diagram for SLAMSolver:
Collaboration graph

Public Member Functions

 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.
 
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::Coneget_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
 

Detailed Description

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.

Constructor & Destructor Documentation

◆ SLAMSolver()

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.

Parameters
paramsParameters for the SLAM solver
data_associationData association module
motion_modelMotion model
execution_timesTimekeeping array
loop_closureLoop closure model

Definition at line 3 of file slam_solver.cpp.

◆ ~SLAMSolver()

virtual SLAMSolver::~SLAMSolver ( )
virtualdefault

Member Function Documentation

◆ add_observations()

virtual void SLAMSolver::add_observations ( const std::vector< common_lib::structures::Cone > &  cones,
rclcpp::Time  cones_timestamp 
)
pure virtual

Add observations to the solver.

Parameters
conesPositions of the observations

Implemented in GraphSLAMSolver, and EKFSLAMSolver.

◆ add_velocities()

virtual void SLAMSolver::add_velocities ( const common_lib::structures::Velocities velocities)
pure virtual

Process new velocity data.

Parameters
velocitiesVelocities data

Implemented in EKFSLAMSolver, and GraphSLAMSolver.

◆ get_associations()

virtual Eigen::VectorXi SLAMSolver::get_associations ( ) const
pure virtual

Implemented in EKFSLAMSolver, and GraphSLAMSolver.

◆ get_covariance()

virtual Eigen::MatrixXd SLAMSolver::get_covariance ( )
pure virtual

Get covariance matrix.

Returns
Eigen::MatrixXd

Implemented in EKFSLAMSolver, and GraphSLAMSolver.

◆ get_lap_counter()

virtual int SLAMSolver::get_lap_counter ( )
pure virtual

Get the lap counter.

Returns
int lap counter

Implemented in EKFSLAMSolver, and GraphSLAMSolver.

◆ get_map_coordinates()

virtual Eigen::VectorXd SLAMSolver::get_map_coordinates ( ) const
pure virtual

Implemented in EKFSLAMSolver, and GraphSLAMSolver.

◆ get_map_estimate()

virtual std::vector< common_lib::structures::Cone > SLAMSolver::get_map_estimate ( )
pure virtual

Get the map estimate object.

Returns
std::vector<common_lib::structures::Cone>

Implemented in EKFSLAMSolver, and GraphSLAMSolver.

◆ get_observations_global()

virtual Eigen::VectorXd SLAMSolver::get_observations_global ( ) const
pure virtual

Implemented in EKFSLAMSolver, and GraphSLAMSolver.

◆ get_pose_estimate()

virtual common_lib::structures::Pose SLAMSolver::get_pose_estimate ( )
pure virtual

Get the pose estimate object.

Returns
common_lib::structures::Pose

Implemented in EKFSLAMSolver, and GraphSLAMSolver.

◆ load_initial_state()

virtual void SLAMSolver::load_initial_state ( const Eigen::VectorXd &  map,
const Eigen::Vector3d &  pose 
)
pure virtual

Loads a previously saved map and pose into the solver.

Parameters
mapcoordinates of the landmarks in the form of [x1, y1, x2, y2, ...] in the global frame
poseinitial pose of the robot in the form of [x, y, theta] in the global frame

Implemented in EKFSLAMSolver, and GraphSLAMSolver.

Here is the caller graph for this function:

◆ set_mission()

void SLAMSolver::set_mission ( common_lib::competition_logic::Mission  mission)

Set the mission.

Parameters
mission

Definition at line 16 of file slam_solver.cpp.

Here is the call graph for this function:

Member Data Documentation

◆ _data_association_

std::shared_ptr<DataAssociationModel> SLAMSolver::_data_association_
protected

Definition at line 25 of file slam_solver.hpp.

◆ _execution_times_

std::shared_ptr<std::vector<double> > SLAMSolver::_execution_times_
protected

Definition at line 30 of file slam_solver.hpp.

◆ _landmark_filter_

std::shared_ptr<LandmarkFilter> SLAMSolver::_landmark_filter_
protected

Definition at line 27 of file slam_solver.hpp.

◆ _last_observation_update_

rclcpp::Time SLAMSolver::_last_observation_update_ = rclcpp::Time(0)
protected

Definition at line 35 of file slam_solver.hpp.

◆ _last_pose_update_

rclcpp::Time SLAMSolver::_last_pose_update_ = rclcpp::Time(0)
protected

Definition at line 34 of file slam_solver.hpp.

◆ _loop_closure_

std::shared_ptr<LoopClosure> SLAMSolver::_loop_closure_
protected

Definition at line 32 of file slam_solver.hpp.

◆ _mission_

common_lib::competition_logic::Mission SLAMSolver::_mission_ = common_lib::competition_logic::Mission::NONE
protected

Definition at line 28 of file slam_solver.hpp.

◆ _motion_model_

std::shared_ptr<V2PMotionModel> SLAMSolver::_motion_model_
protected

Definition at line 26 of file slam_solver.hpp.

◆ _params_

SLAMParameters SLAMSolver::_params_
protected

Definition at line 24 of file slam_solver.hpp.

◆ _received_first_velocities_

bool SLAMSolver::_received_first_velocities_
protected
Initial value:
=
false

Definition at line 37 of file slam_solver.hpp.

◆ lap_counter_

int SLAMSolver::lap_counter_ = 0
protected

Definition at line 40 of file slam_solver.hpp.


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