Public Member Functions | Public Attributes | Private Attributes | List of all members
steering::EKF Class Reference

#include <ekf.hpp>

Public Member Functions

Matrix3d covariance_to_eigen (const double covariance[16]) const
 Converts a covariance given by a double array to an Eigen matrix. More...
 
void eigen_to_covariance (const Matrix3d &covariance_eigen, double covariance[16]) const
 Converts a covariance given by an Eigen matrix to a double array. More...
 
 EKF ()
 
Matrix23d get_controller_gain (const Control &control) const
 Returns the gain of the controller. More...
 
Matrix2d get_motion_covariance (const State &state, const Control &control, double integration_step) const
 Returns the motion covariance in control space. More...
 
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. More...
 
Matrix3d get_observation_covariance () const
 Returns the observation covariance. More...
 
Matrix3d get_observation_jacobi () const
 Computes the Jacobian of the observation equations with respect to the state. More...
 
Matrix3d get_rotation_matrix (double angle) const
 Returns the rotation matrix from a global frame to a local frame. More...
 
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. More...
 
void set_parameters (const Motion_Noise &motion_noise, const Measurement_Noise &measurement_noise, const Controller &_controller)
 Sets the parameters required by the EKF. More...
 
void update (const State_With_Covariance &state_pred, State_With_Covariance &state_corr) const
 Predicts the covariances. More...
 

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 Overload operator new for fixed-size vectorizable Eigen member variable. More...
 

Private Attributes

Controller controller_
 Feedback controller. More...
 
Matrix3d I_
 Identity matrix. More...
 
Measurement_Noise measurement_noise_
 Measurement noise. More...
 
Motion_Noise motion_noise_
 Motion noise. More...
 

Detailed Description

Definition at line 48 of file ekf.hpp.

Constructor & Destructor Documentation

◆ EKF()

steering::EKF::EKF ( )

Constructor

Definition at line 41 of file ekf.cpp.

Member Function Documentation

◆ covariance_to_eigen()

Matrix3d steering::EKF::covariance_to_eigen ( const double  covariance[16]) const

Converts a covariance given by a double array to an Eigen matrix.

Definition at line 54 of file ekf.cpp.

◆ eigen_to_covariance()

void steering::EKF::eigen_to_covariance ( const Matrix3d covariance_eigen,
double  covariance[16] 
) const

Converts a covariance given by an Eigen matrix to a double array.

Definition at line 67 of file ekf.cpp.

◆ get_controller_gain()

Matrix23d steering::EKF::get_controller_gain ( const Control control) const

Returns the gain of the controller.

Definition at line 205 of file ekf.cpp.

◆ get_motion_covariance()

Matrix2d steering::EKF::get_motion_covariance ( const State state,
const Control control,
double  integration_step 
) const

Returns the motion covariance in control space.

Definition at line 186 of file ekf.cpp.

◆ get_motion_jacobi()

void steering::EKF::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.

Definition at line 78 of file ekf.cpp.

◆ get_observation_covariance()

Matrix3d steering::EKF::get_observation_covariance ( ) const

Returns the observation covariance.

Definition at line 196 of file ekf.cpp.

◆ get_observation_jacobi()

Matrix3d steering::EKF::get_observation_jacobi ( ) const

Computes the Jacobian of the observation equations with respect to the state.

Definition at line 181 of file ekf.cpp.

◆ get_rotation_matrix()

Matrix3d steering::EKF::get_rotation_matrix ( double  angle) const

Returns the rotation matrix from a global frame to a local frame.

Definition at line 214 of file ekf.cpp.

◆ predict()

void steering::EKF::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.

Definition at line 227 of file ekf.cpp.

◆ set_parameters()

void steering::EKF::set_parameters ( const Motion_Noise motion_noise,
const Measurement_Noise measurement_noise,
const Controller _controller 
)

Sets the parameters required by the EKF.

Definition at line 46 of file ekf.cpp.

◆ update()

void steering::EKF::update ( const State_With_Covariance state_pred,
State_With_Covariance state_corr 
) const

Predicts the covariances.

Definition at line 251 of file ekf.cpp.

Member Data Documentation

◆ controller_

Controller steering::EKF::controller_
private

Feedback controller.

Definition at line 102 of file ekf.hpp.

◆ EIGEN_MAKE_ALIGNED_OPERATOR_NEW

steering::EKF::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Overload operator new for fixed-size vectorizable Eigen member variable.

Definition at line 92 of file ekf.hpp.

◆ I_

Matrix3d steering::EKF::I_
private

Identity matrix.

Definition at line 105 of file ekf.hpp.

◆ measurement_noise_

Measurement_Noise steering::EKF::measurement_noise_
private

Measurement noise.

Definition at line 99 of file ekf.hpp.

◆ motion_noise_

Motion_Noise steering::EKF::motion_noise_
private

Motion noise.

Definition at line 96 of file ekf.hpp.


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


steering_functions
Author(s): Holger Banzhaf
autogenerated on Mon Dec 11 2023 03:27:44