Implements Extended Kalman Filter as an estimator within the ROS framework.
More...
#include <ekf_estimator.h>
|
| | EKFEstimator () |
| | Constructor for EKFEstimator.
|
| |
| void | init (ros::NodeHandle &nh) |
| | Initialize EKF.
|
| |
| bool | updateOnce (quad_msgs::RobotState &last_robot_state_msg_) |
| | Perform EKF update once.
|
| |
| | StateEstimator () |
| | Constructor for StateEstimator.
|
| |
| void | readIMU (const sensor_msgs::Imu::ConstPtr &last_imu_msg, Eigen::Vector3d &fk, Eigen::Vector3d &wk, Eigen::Quaterniond &qk) |
| | Read IMU data.
|
| |
| void | readJointEncoder (const sensor_msgs::JointState::ConstPtr &last_joint_state_msg, Eigen::VectorXd &jk) |
| | Read joint encoder data.
|
| |
| void | loadMocapMsg (geometry_msgs::PoseStamped::ConstPtr last_mocap_msg) |
| | Load Mocap data to protected variable.
|
| |
| void | loadSensorMsg (sensor_msgs::Imu last_imu_msg, sensor_msgs::JointState last_joint_state_msg) |
| | Load imu and joint encoder data to protected variables.
|
| |
|
|
ros::NodeHandle | nh_ |
| | Nodehandle to get param.
|
| |
|
|
quad_msgs::RobotState | state_est_ |
| | Last state estimate.
|
| |
|
std::shared_ptr< quad_utils::QuadKD > | quadKD_ |
| | QuadKD class.
|
| |
|
geometry_msgs::PoseStamped::ConstPtr | last_mocap_msg_ |
| | Last mocap data.
|
| |
|
sensor_msgs::Imu | last_imu_msg_ |
| | Most recent IMU data.
|
| |
|
sensor_msgs::JointState | last_joint_state_msg_ |
| | Most recent joint data.
|
| |
Implements Extended Kalman Filter as an estimator within the ROS framework.
◆ EKFEstimator()
| EKFEstimator::EKFEstimator |
( |
| ) |
|
◆ init()
| void EKFEstimator::init |
( |
ros::NodeHandle & |
nh | ) |
|
|
virtual |
Initialize EKF.
- Parameters
-
| [in] | nh | Node Handler to load parameters from yaml file |
Implements StateEstimator.
◆ updateOnce()
| bool EKFEstimator::updateOnce |
( |
quad_msgs::RobotState & |
last_robot_state_msg_ | ) |
|
|
virtual |
Perform EKF update once.
- Parameters
-
| [out] | last_robot_state_msg_ | |
Implements StateEstimator.
The documentation for this class was generated from the following files:
- robot_driver/include/robot_driver/estimators/ekf_estimator.h
- robot_driver/src/estimators/ekf_estimator.cpp