Quad-SDK
Loading...
Searching...
No Matches
Classes | Public Member Functions | Private Attributes | List of all members
CompFilterEstimator Class Reference

Implements complementary filter as an estimator within the ROS framework. More...

#include <comp_filter_estimator.h>

Inheritance diagram for CompFilterEstimator:
Inheritance graph
[legend]
Collaboration diagram for CompFilterEstimator:
Collaboration graph
[legend]

Classes

struct  Filter
 Struct of second-order low/high pass filter with derivative/intergral. More...
 

Public Member Functions

 CompFilterEstimator ()
 Constructor for CompFilterEstimator.
 
void init (ros::NodeHandle &nh)
 Initialize Complementary Filter.
 
void mocapCallBackHelper (const geometry_msgs::PoseStamped::ConstPtr &msg, const Eigen::Vector3d &pos)
 Helper function to filter mocap data.
 
bool updateOnce (quad_msgs::RobotState &last_robot_state_msg)
 Perform CF update once.
 
- Public Member Functions inherited from StateEstimator
 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.
 

Private Attributes

Filter low_pass_filter
 Low pass filter.
 
Filter high_pass_filter
 High pass filter.
 
std::vector< double > high_pass_a_
 High Pass States.
 
std::vector< double > high_pass_b_
 
std::vector< double > high_pass_c_
 
std::vector< double > high_pass_d_
 
std::vector< double > low_pass_a_
 Low Pass States.
 
std::vector< double > low_pass_b_
 
std::vector< double > low_pass_c_
 
std::vector< double > low_pass_d_
 
Eigen::Vector3d vel_estimate_
 Best estimate of velocity.
 
Eigen::Vector3d mocap_vel_estimate_
 Best estimate of velocity from mocap diff.
 
Eigen::Vector3d imu_vel_estimate_
 Best estimate of imu velocity.
 
ros::Time last_mocap_time_
 Last mocap time.
 
ros::NodeHandle nh_
 Nodehandle to get param.
 

Additional Inherited Members

- Protected Attributes inherited from StateEstimator
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 complementary filter as an estimator within the ROS framework.

Constructor & Destructor Documentation

◆ CompFilterEstimator()

CompFilterEstimator::CompFilterEstimator ( )

Constructor for CompFilterEstimator.

Returns
Constructed object of type CompFilterEstimator

Member Function Documentation

◆ init()

void CompFilterEstimator::init ( ros::NodeHandle &  nh)
virtual

Initialize Complementary Filter.

Parameters
[in]nhROS Node Handler used to load parameters from yaml file

Implements StateEstimator.

◆ updateOnce()

bool CompFilterEstimator::updateOnce ( quad_msgs::RobotState &  last_robot_state_msg)
virtual

Perform CF update once.

Parameters
[out]last_robot_state_msg

Implements StateEstimator.


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