Quad-SDK
Loading...
Searching...
No Matches
Public Member Functions | Protected Attributes | List of all members
StateEstimator Class Referenceabstract

#include <state_estimator.h>

Inheritance diagram for StateEstimator:
Inheritance graph
[legend]

Public Member Functions

 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.
 

Protected Attributes

quad_msgs::RobotState state_est_
 Last state estimate.
 
std::shared_ptr< quad_utils::QuadKDquadKD_
 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.
 

Detailed Description

Implements an abstract class for state estimator. This class provides an interface for different types of estimators

StateEstimator provides an abstract state estimator class

Constructor & Destructor Documentation

◆ StateEstimator()

StateEstimator::StateEstimator ( )

Constructor for StateEstimator.

Returns
Constructed object of type StateEstimator

Member Function Documentation

◆ init()

virtual void StateEstimator::init ( ros::NodeHandle &  nh)
pure virtual

Virtual function for initialize filters, should be defined in derived class.

Parameters
[in]nh_ROS Node Ha

Implemented in CompFilterEstimator, and EKFEstimator.

◆ loadMocapMsg()

void StateEstimator::loadMocapMsg ( geometry_msgs::PoseStamped::ConstPtr  last_mocap_msg)

Load Mocap data to protected variable.

Parameters
[in]last_mocap_msgMocap 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_msgimu msgs
[in]last_joint_state_msgjoint 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_msgIMU sensor message
[out]fkLinear acceleration
[out]wkAngular acceleration
[out]qkOrientation 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_msgJoint state sensor message
[out]jkJointstate 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_msgrobot state

Implemented in CompFilterEstimator, and EKFEstimator.


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