Go to the documentation of this file.
11 #include <rm_msgs/BalanceState.h>
19 hardware_interface::EffortJointInterface>
35 geometry_msgs::Twist
odometry()
override;
38 Eigen::Matrix<double, CONTROL_DIM, STATE_DIM>
k_{};
39 Eigen::Matrix<double, STATE_DIM, STATE_DIM>
a_{},
q_{};
40 Eigen::Matrix<double, STATE_DIM, CONTROL_DIM>
b_{};
41 Eigen::Matrix<double, CONTROL_DIM, CONTROL_DIM>
r_{};
42 Eigen::Matrix<double, STATE_DIM, 1>
x_;
58 typedef std::shared_ptr<realtime_tools::RealtimePublisher<rm_msgs::BalanceState>>
RtpublisherPtr;
std::shared_ptr< realtime_tools::RealtimePublisher< rm_msgs::BalanceState > > RtpublisherPtr
geometry_msgs::Twist odometry() override
hardware_interface::ImuSensorHandle imu_handle_
hardware_interface::JointHandle right_wheel_joint_handle_
ros::Time last_block_time_
Eigen::Matrix< double, CONTROL_DIM, STATE_DIM > k_
hardware_interface::JointHandle left_wheel_joint_handle_
static const int STATE_DIM
Eigen::Matrix< double, CONTROL_DIM, CONTROL_DIM > r_
void block(const ros::Time &time, const ros::Duration &period)
hardware_interface::JointHandle right_momentum_block_joint_handle_
Eigen::Matrix< double, STATE_DIM, STATE_DIM > q_
double anti_block_effort_
geometry_msgs::Vector3 angular_vel_base_
RtpublisherPtr state_pub_
bool balance_state_changed_
void normal(const ros::Time &time, const ros::Duration &period)
Eigen::Matrix< double, STATE_DIM, CONTROL_DIM > b_
BalanceController()=default
hardware_interface::JointHandle left_momentum_block_joint_handle_
Eigen::Matrix< double, STATE_DIM, 1 > x_
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
static const int CONTROL_DIM
void moveJoint(const ros::Time &time, const ros::Duration &period) override
Eigen::Matrix< double, STATE_DIM, STATE_DIM > a_
double position_clear_threshold_