8.14 Remote Controller Interface
1. Remote Controller Event Data
-
Description: Obtain raw data from the remote controller. Applicable to all Walker Tienkung models.
-
Communication type: topic
-
Topic name:
/sbus_data/event -
Message type:
bodyctrl_msgs::msg::SbusData -
Message format:
int32 KEY_NONE = 0
int32 KEY_A_UP = 1 # A key release event
int32 KEY_A_DOWN = 2 # A key press event
int32 KEY_B_UP = 3 # B key release event
int32 KEY_B_DOWN = 4 # B key press event
int32 KEY_C_UP = 5 # C key release event
int32 KEY_C_DOWN = 6 # C key press event
int32 KEY_D_UP = 7 # D key release event
int32 KEY_D_DOWN = 8 # D key press event
int32 KEY_E_UP = 9 # E key up‑switch event
int32 KEY_E_MID = 10 # E key center‑switch event
int32 KEY_E_DOWN = 11 # E key down‑switch event
int32 KEY_F_UP = 12 # F key up‑switch event
int32 KEY_F_MID = 13 # F key center‑switch event
int32 KEY_F_DOWN = 14 # F key down‑switch event
int32 KEY_G_LEFT = 15 # G key left‑switch event
int32 KEY_G_MID = 16 # G key center‑switch event
int32 KEY_G_RIGHT = 17 # G key right‑switch event
int32 KEY_H_LEFT = 18 # H key left‑switch event
int32 KEY_H_MID = 19 # H key center‑switch event
int32 KEY_H_RIGHT = 20 # H key right‑switch event
std_msgs/Header header
int32 key_event_new # New key event value
int32 key_event_old # Previous key event value
# For example, when the G key moves from right to center:
# key_event_old = KEY_G_RIGHT, key_event_new = KEY_G_MID
int8 button_a # A key value; -1: released, 1: pressed
int8 button_b # B key value; -1: released, 1: pressed
int8 button_c # C key value; -1: released, 1: pressed
int8 button_d # D key value; -1: released, 1: pressed
int8 button_e # E key value; <-0.5: up, -0.5~0.5: center, >0.5: down
int8 button_f # F key value; <-0.5: up, -0.5~0.5: center, >0.5: down
int8 button_g # G key value; <-0.5: left, -0.5~0.5: center, >0.5: right
int8 button_h # H key value; <-0.5: right, -0.5~0.5: center, >0.5: left
float32 x1 # Left stick X‑axis (left/right), range -1.0~1.0
float32 y1 # Left stick Y‑axis (up/down), range -1.0~1.0
float32 x2 # Right stick X‑axis (left/right), range -1.0~1.0
float32 y2 # Right stick Y‑axis (up/down), range -1.0~1.0
2. Subscribe to remote control topic
Note: from bodyctrl_msgs.msg import SbusData imports a custom remote control message definition. To ensure this message definition is found, you need to source the environment variables before running the code:
- x86:
source /home/ubuntu/ros2ws/install/setup.bash - orin:
source /home/nvidia/lyre_ros2/install/setup.bash
Code example:
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: "None", 1: "A key released", 2: "A key pressed", 3: "B key released",
4: "B key pressed", 5: "C key released", 6: "C key pressed", 7: "D key released",
8: "D key pressed", 9: "E key up", 10: "E key return to center",
11: "E key down", 12: "F key up", 13: "F key return to center",
14: "F key down", 15: "G key left", 16: "G key return to center",
17: "G key right", 18: "H key left", 19: "H key return to center",
20: "H key right"
}
def listener_callback(self, msg: SbusData):
print("🎮 [SBUS Event]")
print(f" 🆕 Current Event: {self.key_event_map.get(msg.key_event_new, f'Unknow({msg.key_event_new})')}")
print(f" 🕒 Prev Event: {self.key_event_map.get(msg.key_event_old, f'Unknow({msg.key_event_old})')}")
def key_state(val):
return '✅ Pressed' if val == 1 else '❌ Released'
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, ['⬆ Up', '⏺ Center', '⬇ Down'])}")
print(f" F: {three_state(msg.button_f, ['⬆ Up', '⏺ Center', '⬇ Down'])}")
print(f" G: {three_state(msg.button_g, ['⬅ Left', '⏺ Center', '➡ Right'])}")
print(f" H: {three_state(msg.button_h, ['➡ Right', '⏺ Center', '⬅ Left'])}")
print("\n🕹 Joystick Status (Range -1.0 ~ 1.0):")
print(f" Left Joystick: X={msg.x1:.2f}, Y={msg.y1:.2f}")
print(f" Right Joystick: 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("🛑 exited")
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()