Formula Student Autonomous Systems
The code for the main driverless system
Loading...
Searching...
No Matches
motion_models.hpp File Reference
#include <eigen3/Eigen/Dense>
#include <functional>
#include <map>
#include <memory>
#include <rclcpp/rclcpp.hpp>
#include <typeinfo>
Include dependency graph for motion_models.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  MotionUpdate
 Struct for data retrieved by the IMU. More...
 
class  MotionModel
 Abstract Moiton Model class designed to be implemented by the different motion models. More...
 
class  ImuVelocityModel
 Motion estimation that uses the specific values of the x and y axis accelerations, being the angle of the vehicle and its position independent. More...
 
class  NormalVelocityModel
 Motion estimation that uses the module of the velocity and the rotational velocity. More...
 

Variables

const std::map< std::string, std::function< std::shared_ptr< MotionModel >(const Eigen::MatrixXf &)>, std::less<> > motion_model_constructors
 Map object to map strings from launch file parameter to constructor.
 

Variable Documentation

◆ motion_model_constructors

const std::map<std::string, std::function<std::shared_ptr<MotionModel>(const Eigen::MatrixXf &)>, std::less<> > motion_model_constructors
Initial value:
= {
{"normal_velocity_model",
[](const Eigen::MatrixXf &process_noise_covariance_matrix)
-> std::shared_ptr<MotionModel> {
return std::make_shared<NormalVelocityModel>(process_noise_covariance_matrix);
}},
{"imu_velocity_model",
[](const Eigen::MatrixXf &process_noise_covariance_matrix)
-> std::shared_ptr<MotionModel> {
return std::make_shared<ImuVelocityModel>(process_noise_covariance_matrix);
}}}

Map object to map strings from launch file parameter to constructor.

Definition at line 185 of file motion_models.hpp.