Class EKF
- Defined in File ekf.hpp 
Class Documentation
- 
class EKF
- Public Functions - 
EKF()
- Constructor 
 - 
void set_parameters(const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise, const Controller &_controller)
- Sets the parameters required by the EKF. 
 - 
Matrix3d covariance_to_eigen(const double covariance[16]) const
- Converts a covariance given by a double array to an Eigen matrix. 
 - 
void eigen_to_covariance(const Matrix3d &covariance_eigen, double covariance[16]) const
- Converts a covariance given by an Eigen matrix to a double array. 
 - 
void get_motion_jacobi(const State &state, const Control &control, double integration_step, Matrix3d &F_x, Matrix32d &F_u) const
- Computes the Jacobians of the motion equations with respect to the state and control. 
 - 
Matrix3d get_observation_jacobi() const
- Computes the Jacobian of the observation equations with respect to the state. 
 - 
Matrix2d get_motion_covariance(const State &state, const Control &control, double integration_step) const
- Returns the motion covariance in control space. 
 - 
Matrix3d get_rotation_matrix(double angle) const
- Returns the rotation matrix from a global frame to a local frame. 
 - 
void predict(const State_With_Covariance &state, const Control &control, double integration_step, State_With_Covariance &state_pred) const
- Predicts the covariances based on the paper: Rapidly-exploring random belief trees for motion planning under uncertainty, A. Bry and N. Roy, IEEE ICRA 2011. 
 - 
void update(const State_With_Covariance &state_pred, State_With_Covariance &state_corr) const
- Predicts the covariances. 
 - Public Members - EIGEN_MAKE_ALIGNED_OPERATOR_NEW
- Overload operator new for fixed-size vectorizable Eigen member variable. 
 
- 
EKF()