Class KalmanFilterParam
Defined in File kalman_filter_param.hpp
Inheritance Relationships
Base Type
public state_observer::StateObserverParam
(Class StateObserverParam)
Class Documentation
-
class KalmanFilterParam : public state_observer::StateObserverParam
Parameters for the Kalman Filter observer.
The
KalmanFilterParam
class extendsStateObserverParam
to include the process noise covariance matrixQ
, measurement noise covariance matrixR
, and the initial error covariance matrixP0
specific to the Kalman Filter observer.Public Types
Public Functions
-
inline KalmanFilterParam()
Default constructor.
-
inline virtual ~KalmanFilterParam()
Destructor.
Initialize the parameters from a ROS 2 lifecycle node.
This method reads the parameters from the provided node and initializes the state-space matrices and covariance matrices.
- Parameters:
node – Shared pointer to an
rclcpp_lifecycle::LifecycleNode
.- Throws:
std::runtime_error – if parameter retrieval fails.
-
inline Eigen::MatrixXd get_R()
Get the measurement noise covariance matrix
R
.- Returns:
Measurement noise covariance matrix
R_
(q x q).
-
inline Eigen::MatrixXd get_Q()
Get the process noise covariance matrix
Q
.- Returns:
Process noise covariance matrix
Q_
(n x n).
-
inline Eigen::MatrixXd get_P0()
Get the initial error covariance matrix
P0
.- Returns:
Initial error covariance matrix
P0_
(n x n).
-
virtual std::string get_type() const override
Get the type of the state observer.
- Returns:
A string representing the type of the state observer.
-
inline KalmanFilterParam()