8.14 遥控器接口
1. 遥控器事件数据
-
说明:获取遥控器原始数据,适用于天工行者全系列。
-
控制方式:topic
-
话题名称:
/sbus_data/event -
类型:
bodyctrl_msgs::msg::SbusData.msg -
数据格式:
int32 KEY_NONE =0
int32 KEY_A_UP =1 # A 键抬起事件
int32 KEY_A_DOWN =2 # A 键按下事件
int32 KEY_B_UP =3 # B 键抬起事件
int32 KEY_B_DOWN =4 # B 键按下事件
int32 KEY_C_UP =5 # C 键抬起事件
int32 KEY_C_DOWN =6 # C 键按下事件
int32 KEY_D_UP =7 # D 键抬起事件
int32 KEY_D_DOWN =8 # D 键按下事件
int32 KEY_E_UP =9 # E 键上拨事件
int32 KEY_E_MID =10 # E 键回中事件
int32 KEY_E_DOWN =11 # E 键下拨事件
int32 KEY_F_UP =12 # F 键上拨事件
int32 KEY_F_MID =13 # F 键回中事件
int32 KEY_F_DOWN =14 # F 键下拨事件
int32 KEY_G_LEFT =15 # G 键左拨事件
int32 KEY_G_MID =16 # G 键回中事件
int32 KEY_G_RIGHT =17 # G 键右拨事件
int32 KEY_H_LEFT =18 # H 键左拨事件
int32 KEY_H_MID =19 # H 键回中事件
int32 KEY_H_RIGHT =20 # H 键右拨事件
std_msgs/Header header
int32 key_event_new # 按键事件新值
int32 key_event_old # 按键事件旧值
# 例如 G 键从右边拨到中间位置 ,
# 则key_event_old =KEY_G_RIGHT ,key_event_new =KEY_G_MID
int8 button_a # A 键键值 , -1 :松开 , 1 :按下
int8 button_b # B 键键值 , -1 :松开 , 1 :按下
int8 button_c # C 键键值 , -1 :松开 , 1 :按下
int8 button_d # D 键键值 , -1 :松开 , 1 :按下
int8 button_e # E 键键值 , <-0.5 :上拨 , -0.5~0.5: 中间 , >0.5 :下拨
int8 button_f # F 键键值 , <-0.5 :上拨 , -0.5~0.5: 中间 , >0.5 :下拨
int8 button_g # G 键键值 , <-0.5 :左拨 , -0.5~0.5: 中间 , >0.5 :右拨
int8 button_h # H 键键值 , <-0.5 :右拨 , -0.5~0.5: 中间 , >0.5 :左拨
float32 x1 # 左摇杆 X 方向值(左右方向) ,范围-1.0~1.0
float32 y1 # 左摇杆 Y 方向值(上下方向) ,范围-1.0~1.0
float32 x2 # 右摇杆 X 方向值(左右方向) ,范围-1.0~1.0
float32 y2 # 右摇杆 Y 方向值(上下方向) ,范围-1.0~1.0
2. 订阅遥控器话题
注意:from bodyctrl_msgs.msg import SbusData是导入自定义的遥控器消息定义,为了让可以找到该消息定义,需要在运行代码前先source环境变量:
- x86:
source /home/ubuntu/ros2ws/install/setup.bash - orin:
source /home/nvidia/lyre_ros2/install/setup.bash
简单代码如下:
import rclpy
from rclpy.node import Node
from bodyctrl_msgs.msg import SbusData
class GrabMonitor(Node):
def __init__(self):
super().__init__('sbus_event_listener')
self.subscription = self.create_subscription(
SbusData, '/sbus_data/event', self.listener_callback, 10
)
self.subscription
self.key_event_map = {
0: "无", 1: "A键抬起", 2: "A键按下", 3: "B键抬起",
4: "B键按下", 5: "C键抬起", 6: "C键按下", 7: "D键抬起",
8: "D键按下", 9: "E键上拨", 10: "E键回中", 11: "E键下拨",
12: "F键上拨", 13: "F键回中", 14: "F键下拨", 15: "G键左拨",
16: "G键回中", 17: "G键右拨", 18: "H键左拨", 19: "H键回中",
20: "H键右拨"
}
def listener_callback(self, msg: SbusData):
print("🎮 [SBUS 控制事件]")
print(f" 🆕 当前按键事件: {self.key_event_map.get(msg.key_event_new, f'未知({msg.key_event_new})')}")
print(f" 🕒 上次按键事件: {self.key_event_map.get(msg.key_event_old, f'未知({msg.key_event_old})')}")
def key_state(val):
return '✅ 按下' if val == 1 else '❌ 松开'
def three_state(val, labels):
if val < -0.5:
return labels[0]
elif val > 0.5:
return labels[2]
else:
return labels[1]
print("\n🔘 按键状态:")
print(f" A: {key_state(msg.button_a)}")
print(f" B: {key_state(msg.button_b)}")
print(f" C: {key_state(msg.button_c)}")
print(f" D: {key_state(msg.button_d)}")
print(f" E: {three_state(msg.button_e, ['⬆ 上拨', '⏺ 中间', '⬇ 下拨'])}")
print(f" F: {three_state(msg.button_f, ['⬆ 上拨', '⏺ 中间', '⬇ 下拨'])}")
print(f" G: {three_state(msg.button_g, ['⬅ 左拨', '⏺ 中间', '➡ 右拨'])}")
print(f" H: {three_state(msg.button_h, ['➡ 右拨', '⏺ 中间', '⬅ 左拨'])}")
print("\n🕹 摇杆状态(范围 -1.0 ~ 1.0):")
print(f" 左摇杆: X={msg.x1:.2f}, Y={msg.y1:.2f}")
print(f" 右摇杆: X={msg.x2:.2f}, Y={msg.y2:.2f}")
print("-" * 50)
def main(args=None):
rclpy.init(args=args)
node = GrabMonitor()
try:
rclpy.spin(node)
except KeyboardInterrupt:
print("🛑 已手动退出")
finally:
node.destroy_node()
try:
rclpy.shutdown()
except rclpy._rclpy_pybind11.RCLError as e:
if "rcl_shutdown already called" in str(e):
pass
else:
raise e
if __name__ == '__main__':
main()