#include <state_estimator.h>
|
| StateEstimator () |
| Constructor for StateEstimator.
|
|
virtual void | init (ros::NodeHandle &nh)=0 |
| Virtual function for initialize filters, should be defined in derived class.
|
|
virtual bool | updateOnce (quad_msgs::RobotState &last_robot_state_msg)=0 |
| Virtual update function for update robot state, should be defined in derived class.
|
|
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.
|
|
|
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 an abstract class for state estimator. This class provides an interface for different types of estimators
StateEstimator provides an abstract state estimator class
◆ StateEstimator()
StateEstimator::StateEstimator |
( |
| ) |
|
◆ init()
virtual void StateEstimator::init |
( |
ros::NodeHandle & |
nh | ) |
|
|
pure virtual |
◆ loadMocapMsg()
void StateEstimator::loadMocapMsg |
( |
geometry_msgs::PoseStamped::ConstPtr |
last_mocap_msg | ) |
|
Load Mocap data to protected variable.
- Parameters
-
[in] | last_mocap_msg | Mocap message |
◆ loadSensorMsg()
void StateEstimator::loadSensorMsg |
( |
sensor_msgs::Imu |
last_imu_msg, |
|
|
sensor_msgs::JointState |
last_joint_state_msg |
|
) |
| |
Load imu and joint encoder data to protected variables.
- Parameters
-
[in] | last_imu_msg | imu msgs |
[in] | last_joint_state_msg | joint state msgs |
◆ readIMU()
void StateEstimator::readIMU |
( |
const sensor_msgs::Imu::ConstPtr & |
last_imu_msg, |
|
|
Eigen::Vector3d & |
fk, |
|
|
Eigen::Vector3d & |
wk, |
|
|
Eigen::Quaterniond & |
qk |
|
) |
| |
Read IMU data.
- Parameters
-
[in] | last_imu_msg | IMU sensor message |
[out] | fk | Linear acceleration |
[out] | wk | Angular acceleration |
[out] | qk | Orientation in quaternion |
◆ readJointEncoder()
void StateEstimator::readJointEncoder |
( |
const sensor_msgs::JointState::ConstPtr & |
last_joint_state_msg, |
|
|
Eigen::VectorXd & |
jk |
|
) |
| |
Read joint encoder data.
- Parameters
-
[in] | last_joint_state_msg | Joint state sensor message |
[out] | jk | Jointstate in vector (12 * 1) |
◆ updateOnce()
virtual bool StateEstimator::updateOnce |
( |
quad_msgs::RobotState & |
last_robot_state_msg | ) |
|
|
pure virtual |
Virtual update function for update robot state, should be defined in derived class.
- Parameters
-
[out] | last_robot_state_msg | robot state |
Implemented in CompFilterEstimator, and EKFEstimator.
The documentation for this class was generated from the following files:
- robot_driver/include/robot_driver/estimators/state_estimator.h
- robot_driver/src/estimators/state_estimator.cpp