#include <state_estimator.h>
|
| Eigen::Matrix< double, 3, 1 > | _attitude = Eigen::Matrix<double, 3, 1>::Zero() |
| |
| Eigen::Matrix< double, 3, 1 > | _lin_vel_body = Eigen::Matrix<double, 3, 1>::Zero() |
| |
| Eigen::Matrix< double, 3, 1 > | _ang_vel = Eigen::Matrix<double, 3, 1>::Zero() |
| |
| Eigen::Matrix< double, 3, 1 > | _lin_vel_world = Eigen::Matrix<double, 3, 1>::Zero() |
| |
| double | _avg_lin_gait_vel_x = 0.0 |
| |
| double | _avg_lin_gait_vel_y = 0.0 |
| |
| double | _avg_ang_gait_vel_z = 0.0 |
| |
| std::vector< double > | _lin_vel_body_x_history |
| |
| std::vector< double > | _lin_vel_body_y_history |
| |
| std::vector< double > | _ang_vel_body_z_history |
| |
| int | gait_iteration = 0 |
| |
| int | number_of_gait_iterations |
| |
| std::string | _node_name = "state_estimation_node" |
| |
| ros::NodeHandlePtr | _node_handle |
| |
| ros::Subscriber | _generalized_position_subscriber |
| |
| ros::Subscriber | _generalized_velocity_subscriber |
| |
| ros::Publisher | _body_twist_state_publisher |
| |
Definition at line 13 of file state_estimator.h.
◆ StateEstimator()
| StateEstimator::StateEstimator |
( |
double |
gait_period, |
|
|
double |
controller_frequency |
|
) |
| |
◆ PrintStates()
| void StateEstimator::PrintStates |
( |
| ) |
|
◆ PublishBodyTwistState()
| void StateEstimator::PublishBodyTwistState |
( |
| ) |
|
◆ UpdateStates()
| void StateEstimator::UpdateStates |
( |
| ) |
|
◆ InitializeROS()
| void StateEstimator::InitializeROS |
( |
| ) |
|
|
private |
◆ GeneralizedPositionCallback()
| void StateEstimator::GeneralizedPositionCallback |
( |
const std_msgs::Float64MultiArrayConstPtr & |
msg | ) |
|
|
private |
◆ GeneralizedVelocityCallback()
| void StateEstimator::GeneralizedVelocityCallback |
( |
const std_msgs::Float64MultiArrayConstPtr & |
msg | ) |
|
|
private |
◆ _attitude
| Eigen::Matrix<double, 3, 1> StateEstimator::_attitude = Eigen::Matrix<double, 3, 1>::Zero() |
|
private |
◆ _lin_vel_body
| Eigen::Matrix<double, 3, 1> StateEstimator::_lin_vel_body = Eigen::Matrix<double, 3, 1>::Zero() |
|
private |
◆ _ang_vel
| Eigen::Matrix<double, 3, 1> StateEstimator::_ang_vel = Eigen::Matrix<double, 3, 1>::Zero() |
|
private |
◆ _lin_vel_world
| Eigen::Matrix<double, 3, 1> StateEstimator::_lin_vel_world = Eigen::Matrix<double, 3, 1>::Zero() |
|
private |
◆ _avg_lin_gait_vel_x
| double StateEstimator::_avg_lin_gait_vel_x = 0.0 |
|
private |
◆ _avg_lin_gait_vel_y
| double StateEstimator::_avg_lin_gait_vel_y = 0.0 |
|
private |
◆ _avg_ang_gait_vel_z
| double StateEstimator::_avg_ang_gait_vel_z = 0.0 |
|
private |
◆ _lin_vel_body_x_history
| std::vector<double> StateEstimator::_lin_vel_body_x_history |
|
private |
◆ _lin_vel_body_y_history
| std::vector<double> StateEstimator::_lin_vel_body_y_history |
|
private |
◆ _ang_vel_body_z_history
| std::vector<double> StateEstimator::_ang_vel_body_z_history |
|
private |
◆ gait_iteration
| int StateEstimator::gait_iteration = 0 |
|
private |
◆ number_of_gait_iterations
| int StateEstimator::number_of_gait_iterations |
|
private |
◆ _node_name
| std::string StateEstimator::_node_name = "state_estimation_node" |
|
private |
◆ _node_handle
| ros::NodeHandlePtr StateEstimator::_node_handle |
|
private |
◆ _generalized_position_subscriber
| ros::Subscriber StateEstimator::_generalized_position_subscriber |
|
private |
◆ _generalized_velocity_subscriber
| ros::Subscriber StateEstimator::_generalized_velocity_subscriber |
|
private |
◆ _body_twist_state_publisher
| ros::Publisher StateEstimator::_body_twist_state_publisher |
|
private |
The documentation for this class was generated from the following files: