mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
repredictor_aloamgarm.h
1 #ifndef REPREDICTOR_ALOAMGARM_H
2 #define REPREDICTOR_ALOAMGARM_H
3 
4 #include <Eigen/Dense>
5 #include <boost/circular_buffer.hpp>
6 #include <std_msgs/Time.h>
7 #include <functional>
8 #include <ros/ros.h>
9 #include <mrs_lib/utils.h>
10 #include <mrs_lib/repredictor.h>
11 
12 namespace mrs_lib
13 {
38 template <class Model>
39 class RepredictorAloamgarm : public Repredictor<Model> {
40 public:
41  /* states, inputs etc. definitions (typedefs, constants etc) //{ */
42 
43  using x_t = typename Model::x_t;
44  using u_t = typename Model::u_t;
45  using z_t = typename Model::z_t;
46  using P_t = typename Model::P_t;
47  using R_t = typename Model::R_t;
48  using Q_t = typename Model::Q_t;
49  using statecov_t = typename Model::statecov_t;
50  using ModelPtr = typename std::shared_ptr<Model>;
51  using history_t = typename Repredictor<Model>::history_t;
52 
53  //}
54 
55 public:
56  /* constructor //{ */
57 
72  RepredictorAloamgarm(const x_t& x0, const P_t& P0, const u_t& u0, const Q_t& Q0, const ros::Time& t0, const ModelPtr& model, const unsigned hist_len,
73  const std::shared_ptr<boost::circular_buffer<double>>& nis_buffer) {
74  Repredictor<Model>::m_sc = {x0, P0, nis_buffer};
76  Repredictor<Model>::m_history = history_t(hist_len);
77  assert(hist_len > 0);
79  };
80  //}
81 };
82 } // namespace mrs_lib
83 
84 
85 #endif // REPREDICTOR_ALOAMGARM_H
mrs_lib::RepredictorAloamgarm::z_t
typename Model::z_t z_t
Measurement vector type .
Definition: repredictor_aloamgarm.h:45
utils.h
Defines various general utility functions.
mrs_lib::RepredictorAloamgarm::P_t
typename Model::P_t P_t
State uncertainty covariance matrix type .
Definition: repredictor_aloamgarm.h:46
mrs_lib::RepredictorAloamgarm::Q_t
typename Model::Q_t Q_t
Process noise covariance matrix type .
Definition: repredictor_aloamgarm.h:48
mrs_lib::RepredictorAloamgarm::x_t
typename Model::x_t x_t
State vector type .
Definition: repredictor_aloamgarm.h:43
mrs_lib::RepredictorAloamgarm::ModelPtr
typename std::shared_ptr< Model > ModelPtr
Shorthand type for a shared pointer-to-Model.
Definition: repredictor_aloamgarm.h:50
mrs_lib
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition: attitude_converter.h:29
mrs_lib::RepredictorAloamgarm::u_t
typename Model::u_t u_t
Input vector type .
Definition: repredictor_aloamgarm.h:44
mrs_lib::RepredictorAloamgarm::R_t
typename Model::R_t R_t
Measurement noise covariance matrix type .
Definition: repredictor_aloamgarm.h:47
mrs_lib::Repredictor
Implementation of the Repredictor for fusing measurements with variable delays.
Definition: repredictor.h:39
mrs_lib::RepredictorAloamgarm::statecov_t
typename Model::statecov_t statecov_t
Helper struct for passing around the state and its covariance in one variable.
Definition: repredictor_aloamgarm.h:49
mrs_lib::RepredictorAloamgarm::RepredictorAloamgarm
RepredictorAloamgarm(const x_t &x0, const P_t &P0, const u_t &u0, const Q_t &Q0, const ros::Time &t0, const ModelPtr &model, const unsigned hist_len, const std::shared_ptr< boost::circular_buffer< double >> &nis_buffer)
Variation of the constructor for kalman filter using nis_buffer (ALOAMGARM)
Definition: repredictor_aloamgarm.h:72
mrs_lib::RepredictorAloamgarm
Implementation of the RepredictorAloamgarm for fusing measurements with variable delays.
Definition: repredictor_aloamgarm.h:39
mrs_lib::Repredictor::addInputChangeWithNoise
std::enable_if_t<!check > addInputChangeWithNoise(const u_t &u, const Q_t &Q, const ros::Time &stamp, const ModelPtr &model=nullptr)
Adds one system input to the history buffer, removing the oldest element in the buffer if it is full.
Definition: repredictor.h:141