balance.h
Go to the documentation of this file.
1 //
2 // Created by yezi on 2022/11/15.
3 //
4 
5 #pragma once
6 
7 #include <rm_common/lqr.h>
11 #include <rm_msgs/BalanceState.h>
12 
14 
16 {
17 using Eigen::Matrix;
18 class BalanceController : public ChassisBase<rm_control::RobotStateInterface, hardware_interface::ImuSensorInterface,
19  hardware_interface::EffortJointInterface>
20 {
22  {
25  };
26 
27 public:
28  BalanceController() = default;
29  bool init(hardware_interface::RobotHW* robot_hw, ros::NodeHandle& root_nh, ros::NodeHandle& controller_nh) override;
30 
31 private:
32  void moveJoint(const ros::Time& time, const ros::Duration& period) override;
33  void normal(const ros::Time& time, const ros::Duration& period);
34  void block(const ros::Time& time, const ros::Duration& period);
35  geometry_msgs::Twist odometry() override;
36  static const int STATE_DIM = 10;
37  static const int CONTROL_DIM = 4;
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_;
44  double position_des_ = 0;
45  double position_offset_ = 0.;
47  double yaw_des_ = 0;
48 
52  bool balance_state_changed_ = false, maybe_block_ = false;
53 
57 
58  typedef std::shared_ptr<realtime_tools::RealtimePublisher<rm_msgs::BalanceState>> RtpublisherPtr;
60  geometry_msgs::Vector3 angular_vel_base_;
61  double roll_, pitch_, yaw_;
62 };
63 
64 } // namespace rm_chassis_controllers
rm_chassis_controllers::BalanceController::RtpublisherPtr
std::shared_ptr< realtime_tools::RealtimePublisher< rm_msgs::BalanceState > > RtpublisherPtr
Definition: balance.h:58
rm_chassis_controllers::ChassisBase
Definition: chassis_base.h:92
rm_chassis_controllers::BalanceController::odometry
geometry_msgs::Twist odometry() override
Definition: balance.cpp:492
rm_chassis_controllers::BalanceController::block_effort_
double block_effort_
Definition: balance.h:51
rm_chassis_controllers::BalanceController::yaw_des_
double yaw_des_
Definition: balance.h:47
chassis_base.h
rm_chassis_controllers::BalanceController::imu_handle_
hardware_interface::ImuSensorHandle imu_handle_
Definition: balance.h:54
rm_chassis_controllers::BalanceController::right_wheel_joint_handle_
hardware_interface::JointHandle right_wheel_joint_handle_
Definition: balance.h:55
rm_chassis_controllers::BalanceController
Definition: balance.h:18
rm_chassis_controllers::BalanceController::NORMAL
@ NORMAL
Definition: balance.h:23
rm_chassis_controllers::BalanceController::block_overtime_
double block_overtime_
Definition: balance.h:51
rm_chassis_controllers::BalanceController::roll_
double roll_
Definition: balance.h:61
rm_chassis_controllers::BalanceController::last_block_time_
ros::Time last_block_time_
Definition: balance.h:50
rm_chassis_controllers::BalanceController::k_
Eigen::Matrix< double, CONTROL_DIM, STATE_DIM > k_
Definition: balance.h:38
rm_chassis_controllers::BalanceController::left_wheel_joint_handle_
hardware_interface::JointHandle left_wheel_joint_handle_
Definition: balance.h:55
rm_chassis_controllers::BalanceController::STATE_DIM
static const int STATE_DIM
Definition: balance.h:36
imu_sensor_interface.h
rm_chassis_controllers::BalanceController::block_angle_
double block_angle_
Definition: balance.h:51
rm_chassis_controllers::BalanceController::r_
Eigen::Matrix< double, CONTROL_DIM, CONTROL_DIM > r_
Definition: balance.h:41
rm_chassis_controllers::BalanceController::block
void block(const ros::Time &time, const ros::Duration &period)
Definition: balance.cpp:468
joint_command_interface.h
hardware_interface::RobotHW
rm_chassis_controllers::BalanceController::right_momentum_block_joint_handle_
hardware_interface::JointHandle right_momentum_block_joint_handle_
Definition: balance.h:56
rm_chassis_controllers::BalanceController::q_
Eigen::Matrix< double, STATE_DIM, STATE_DIM > q_
Definition: balance.h:39
rm_chassis_controllers::BalanceController::anti_block_effort_
double anti_block_effort_
Definition: balance.h:51
rm_chassis_controllers::BalanceController::BLOCK
@ BLOCK
Definition: balance.h:24
rm_chassis_controllers::BalanceController::angular_vel_base_
geometry_msgs::Vector3 angular_vel_base_
Definition: balance.h:60
rm_chassis_controllers::BalanceController::block_time_
ros::Time block_time_
Definition: balance.h:50
rm_chassis_controllers::BalanceController::state_pub_
RtpublisherPtr state_pub_
Definition: balance.h:59
rm_chassis_controllers::BalanceController::balance_state_changed_
bool balance_state_changed_
Definition: balance.h:52
rm_chassis_controllers::BalanceController::position_offset_
double position_offset_
Definition: balance.h:45
rm_chassis_controllers::BalanceController::normal
void normal(const ros::Time &time, const ros::Duration &period)
Definition: balance.cpp:407
hardware_interface::ImuSensorHandle
rm_chassis_controllers::BalanceController::BalanceMode
BalanceMode
Definition: balance.h:21
rm_chassis_controllers::BalanceController::maybe_block_
bool maybe_block_
Definition: balance.h:52
rm_chassis_controllers::BalanceController::yaw_
double yaw_
Definition: balance.h:61
hardware_interface::JointHandle
rm_chassis_controllers::BalanceController::position_des_
double position_des_
Definition: balance.h:44
ros::Time
rm_chassis_controllers::BalanceController::b_
Eigen::Matrix< double, STATE_DIM, CONTROL_DIM > b_
Definition: balance.h:40
rm_chassis_controllers::BalanceController::BalanceController
BalanceController()=default
rm_chassis_controllers::BalanceController::left_momentum_block_joint_handle_
hardware_interface::JointHandle left_momentum_block_joint_handle_
Definition: balance.h:56
rm_chassis_controllers::BalanceController::wheel_radius_
double wheel_radius_
Definition: balance.h:43
rm_chassis_controllers::BalanceController::block_duration_
double block_duration_
Definition: balance.h:51
rm_chassis_controllers::BalanceController::x_
Eigen::Matrix< double, STATE_DIM, 1 > x_
Definition: balance.h:42
rm_chassis_controllers::BalanceController::init
bool init(hardware_interface::RobotHW *robot_hw, ros::NodeHandle &root_nh, ros::NodeHandle &controller_nh) override
Definition: balance.cpp:17
lqr.h
rm_chassis_controllers::BalanceController::CONTROL_DIM
static const int CONTROL_DIM
Definition: balance.h:37
rm_chassis_controllers::BalanceController::moveJoint
void moveJoint(const ros::Time &time, const ros::Duration &period) override
Definition: balance.cpp:322
rm_chassis_controllers::BalanceController::a_
Eigen::Matrix< double, STATE_DIM, STATE_DIM > a_
Definition: balance.h:39
ros::Duration
rm_chassis_controllers::BalanceController::pitch_
double pitch_
Definition: balance.h:61
rm_chassis_controllers::BalanceController::wheel_base_
double wheel_base_
Definition: balance.h:43
rm_chassis_controllers::BalanceController::balance_mode_
int balance_mode_
Definition: balance.h:49
rm_chassis_controllers::BalanceController::block_velocity_
double block_velocity_
Definition: balance.h:51
ros::NodeHandle
rm_chassis_controllers
Definition: balance.h:15
rm_chassis_controllers::BalanceController::position_clear_threshold_
double position_clear_threshold_
Definition: balance.h:46
multi_interface_controller.h


rm_chassis_controllers
Author(s): Qiayuan Liao
autogenerated on Sun May 4 2025 02:57:17