├── readme ├── hand_dog_nonscreen.py └── hand_dog_cv.py /readme: -------------------------------------------------------------------------------- 1 | python3 hand_dog_cv.py enp7s0 笔记本 上 跑这个,这个是带可视化界面的,注意安装依赖 pip install mediapipe 2 | python3 hand_dog_nonscreen.py eth0 这个是 先ssh进到拓展坞,然后执行这个 3 | 请注意 文件都放在unitree_sdk2_python/example 下面执行 4 | 5 | python3 hand_dog_cv.py Run this on enp7s0 notebook. This one has a visual interface. Pay attention to the installation dependencies pip install mediapipe 6 | python3 hand_dog_nonscreen.py eth0 This is to ssh into the expansion dock first, and then execute this 7 | Please note that the files are placed under unitree_sdk2_python/example for execution. 8 | -------------------------------------------------------------------------------- /hand_dog_nonscreen.py: -------------------------------------------------------------------------------- 1 | import time 2 | import sys 3 | import cv2 4 | import numpy as np 5 | import multiprocessing as mp 6 | from multiprocessing import Value 7 | from unitree_sdk2py.core.channel import ChannelFactoryInitialize 8 | from unitree_sdk2py.go2.video.video_client import VideoClient 9 | from unitree_sdk2py.go2.sport.sport_client import SportClient 10 | import mediapipe as mp_mediapipe 11 | import signal 12 | 13 | 14 | # 手势检测类:用于手腕翻转和特定手势的检测 15 | class HandGestureDetector: 16 | def __init__(self, time_window=1.5): 17 | self.previous_flip_status = None # 手掌向上 or 向下 18 | self.flip_count = 0 # 翻转计数 19 | self.hand_open_detected = False # 标记是否检测到五指张开 20 | self.hand_open_detected_time = 0 # 记录五指张开的检测时间 21 | self.gesture_two_detected_time = 0 # 记录手势2的持续检测时间 22 | 23 | def detect_wrist_flip(self, landmarks): 24 | wrist_base = landmarks[0] 25 | thumb_tip = landmarks[4] 26 | return thumb_tip.y > wrist_base.y 27 | 28 | def process_flip(self, landmarks): 29 | current_flip_status = self.detect_wrist_flip(landmarks) 30 | if self.previous_flip_status is not None and self.previous_flip_status != current_flip_status: 31 | self.flip_count += 1 32 | if self.flip_count == 3: # 检测到手腕翻转 33 | self.flip_count = 0 34 | return True # 翻转完成 35 | self.previous_flip_status = current_flip_status 36 | return False 37 | 38 | def is_gesture_one(self, landmarks): 39 | index_tip = landmarks[8] 40 | middle_tip = landmarks[12] 41 | wrist = landmarks[0] 42 | return index_tip.y < wrist.y and middle_tip.y > wrist.y 43 | 44 | def is_gesture_two(self, landmarks): 45 | index_tip = landmarks[8] 46 | middle_tip = landmarks[12] 47 | ring_tip = landmarks[16] 48 | pinky_tip = landmarks[20] 49 | wrist = landmarks[0] 50 | return (index_tip.y < wrist.y and middle_tip.y < wrist.y and 51 | ring_tip.y > wrist.y and pinky_tip.y > wrist.y) 52 | 53 | def is_hand_open(self, landmarks): 54 | thumb_tip = landmarks[4] 55 | index_tip = landmarks[8] 56 | middle_tip = landmarks[12] 57 | ring_tip = landmarks[16] 58 | pinky_tip = landmarks[20] 59 | wrist = landmarks[0] 60 | return (thumb_tip.y < wrist.y and index_tip.y < wrist.y and 61 | middle_tip.y < wrist.y and ring_tip.y < wrist.y and pinky_tip.y < wrist.y) 62 | 63 | def reset(self): 64 | self.previous_flip_status = None 65 | self.flip_count = 0 66 | self.hand_open_detected = False # 重置五指张开状态 67 | self.hand_open_detected_time = 0 # 重置五指张开计时器 68 | self.gesture_two_detected_time = 0 # 重置手势2计时器 69 | 70 | 71 | # 机器人运动控制类 72 | class SportModeTest: 73 | def __init__(self) -> None: 74 | try: 75 | self.client = SportClient() 76 | self.client.SetTimeout(10.0) 77 | self.client.Init() 78 | except AttributeError as e: 79 | print(f"Error initializing SportClient: {e}") 80 | 81 | def RiseSit(self): 82 | try: 83 | self.client.RiseSit() 84 | print("Stand up !!!") 85 | except Exception as e: 86 | print(f"Error executing RiseSit: {e}") 87 | 88 | def Sit(self): 89 | try: 90 | self.client.Sit() 91 | print("Sit down !!!") 92 | except Exception as e: 93 | print(f"Error executing Sit: {e}") 94 | 95 | def Hello(self): 96 | try: 97 | self.client.Hello() 98 | print("Hello !!!") 99 | except Exception as e: 100 | print(f"Error executing Hello: {e}") 101 | 102 | def Heart(self): 103 | try: 104 | self.client.Heart() 105 | print("Heart !!!") 106 | except Exception as e: 107 | print(f"Error executing Heart: {e}") 108 | 109 | 110 | # 初始化视频客户端 111 | def initialize_video_client(network_interface): 112 | ChannelFactoryInitialize(0, network_interface) 113 | client = VideoClient() 114 | client.SetTimeout(3.0) 115 | client.Init() 116 | return client 117 | 118 | 119 | # 获取视频帧 120 | def get_video_frame(client): 121 | code, data = client.GetImageSample() 122 | if code == 0: 123 | image_data = np.frombuffer(bytes(data), dtype=np.uint8) 124 | image = cv2.imdecode(image_data, cv2.IMREAD_COLOR) 125 | return image 126 | else: 127 | print("Get image sample error. code:", code) 128 | return None 129 | 130 | 131 | # 绘制检测区域 132 | def draw_detection_area(image, radius): 133 | height, width, _ = image.shape 134 | center = (width // 2, (height // 2) - 200) 135 | mask = np.zeros((height, width), dtype=np.uint8) 136 | cv2.circle(mask, center, radius, 255, thickness=-1) 137 | return mask 138 | 139 | 140 | # 手势检测线程 141 | def gesture_detection_process(pipe, network_interface, last_action_time_shared): 142 | # 在子进程中重新初始化 143 | client = initialize_video_client(network_interface) 144 | mp_hands = mp_mediapipe.solutions.hands 145 | hands = mp_hands.Hands(min_detection_confidence=0.5, min_tracking_confidence=0.5) 146 | gesture_detector = HandGestureDetector() 147 | radius = 800 148 | 149 | gesture_last_sent = None # 保存上一次发送的手势指令 150 | 151 | while True: 152 | # 获取当前时间 153 | current_time = time.time() 154 | 155 | image = get_video_frame(client) 156 | if image is None: 157 | break 158 | 159 | mask = draw_detection_area(image, radius) 160 | imgRGB = cv2.cvtColor(image, cv2.COLOR_BGR2RGB) 161 | masked_image = cv2.bitwise_and(imgRGB, imgRGB, mask=mask) 162 | result = hands.process(masked_image) 163 | 164 | if result.multi_hand_landmarks: 165 | for handLms in result.multi_hand_landmarks: 166 | print("Detected hand landmarks") 167 | 168 | # 检测五指张开 169 | if not gesture_detector.hand_open_detected: 170 | if gesture_detector.is_hand_open(handLms.landmark): 171 | gesture_detector.hand_open_detected = True 172 | gesture_detector.hand_open_detected_time = current_time # 记录五指张开时间 173 | print("Hand open detected, entering gesture detection mode") 174 | else: 175 | if current_time - gesture_detector.hand_open_detected_time > 5: 176 | gesture_detector.reset() 177 | print("No actions detected within 5 seconds, resetting to hand open detection") 178 | continue 179 | 180 | if gesture_detector.process_flip(handLms.landmark) and gesture_last_sent != "flip_detected": 181 | print("Flip detected") 182 | pipe.send("flip_detected") 183 | 184 | gesture_detector.reset() 185 | gesture_last_sent = "flip_detected" 186 | elif gesture_detector.is_gesture_one(handLms.landmark) and gesture_last_sent != "gesture_one_detected": 187 | print("Gesture 1 detected") 188 | pipe.send("gesture_one_detected") 189 | 190 | gesture_detector.reset() 191 | gesture_last_sent = "gesture_one_detected" 192 | elif gesture_detector.is_gesture_two(handLms.landmark) and gesture_last_sent != "gesture_two_detected": 193 | print("Gesture 2 detected") 194 | pipe.send("gesture_two_detected") 195 | 196 | gesture_detector.reset() 197 | gesture_last_sent = "gesture_two_detected" 198 | else: 199 | gesture_last_sent = None # 如果没有手势,重置最后发送的手势 200 | 201 | 202 | # 机器人运动控制线程 203 | def robot_control_process(pipe, network_interface, last_action_time_shared): 204 | # 在子进程中重新初始化 205 | ChannelFactoryInitialize(0, network_interface) 206 | robot = SportModeTest() 207 | dog_is_standing = False 208 | 209 | while True: 210 | try: 211 | gesture = pipe.recv() # 等待接收手势指令 212 | print(f"Received gesture: {gesture}") 213 | 214 | if gesture == "flip_detected": 215 | if dog_is_standing: 216 | robot.Sit() 217 | dog_is_standing = False 218 | else: 219 | robot.RiseSit() 220 | dog_is_standing = True 221 | 222 | elif gesture == "gesture_one_detected": 223 | robot.Hello() 224 | 225 | elif gesture == "gesture_two_detected": 226 | robot.Heart() 227 | 228 | except EOFError: 229 | break 230 | 231 | 232 | # 捕获信号处理,确保子进程能够优雅关闭 233 | def signal_handler(sig, frame): 234 | print("Signal received, terminating...") 235 | sys.exit(0) 236 | 237 | 238 | # 主函数 239 | def main(): 240 | # 捕获系统信号 (如 Ctrl+C) 并终止进程 241 | signal.signal(signal.SIGINT, signal_handler) 242 | signal.signal(signal.SIGTERM, signal_handler) 243 | 244 | parent_conn, child_conn = mp.Pipe() 245 | network_interface = sys.argv[1] # 获取网络接口 246 | 247 | # 创建一个共享的冷却时间变量 248 | last_action_time_shared = Value('d', time.time()) 249 | 250 | # 创建手势检测进程和机器人控制进程 251 | p1 = mp.Process(target=gesture_detection_process, args=(parent_conn, network_interface, last_action_time_shared)) 252 | p2 = mp.Process(target=robot_control_process, args=(child_conn, network_interface, last_action_time_shared)) 253 | 254 | p1.start() 255 | p2.start() 256 | 257 | try: 258 | p1.join() 259 | p2.join() 260 | except KeyboardInterrupt: 261 | print("KeyboardInterrupt caught, terminating processes...") 262 | finally: 263 | # 确保所有子进程被终止 264 | p1.terminate() 265 | p2.terminate() 266 | p1.join() 267 | p2.join() 268 | 269 | 270 | if __name__ == "__main__": 271 | main() 272 | -------------------------------------------------------------------------------- /hand_dog_cv.py: -------------------------------------------------------------------------------- 1 | import time 2 | import sys 3 | import cv2 4 | import numpy as np 5 | import multiprocessing as mp 6 | from multiprocessing import Value 7 | from unitree_sdk2py.core.channel import ChannelFactoryInitialize 8 | from unitree_sdk2py.go2.video.video_client import VideoClient 9 | from unitree_sdk2py.go2.sport.sport_client import SportClient 10 | import mediapipe as mp_mediapipe 11 | import signal 12 | 13 | 14 | # 手势检测类:用于手腕翻转和特定手势的检测 15 | class HandGestureDetector: 16 | def __init__(self, time_window=1.5): 17 | self.previous_flip_status = None # 手掌向上 or 向下 18 | self.flip_count = 0 # 翻转计数 19 | self.hand_open_detected = False # 标记是否检测到五指张开 20 | self.hand_open_detected_time = 0 # 记录五指张开的检测时间 21 | self.gesture_two_detected_time = 0 # 记录手势2的持续检测时间 22 | 23 | def detect_wrist_flip(self, landmarks): 24 | wrist_base = landmarks[0] 25 | thumb_tip = landmarks[4] 26 | return thumb_tip.y > wrist_base.y 27 | 28 | def process_flip(self, landmarks): 29 | current_flip_status = self.detect_wrist_flip(landmarks) 30 | if self.previous_flip_status is not None and self.previous_flip_status != current_flip_status: 31 | self.flip_count += 1 32 | if self.flip_count == 3: # 检测到手腕翻转 33 | self.flip_count = 0 34 | return True # 翻转完成 35 | self.previous_flip_status = current_flip_status 36 | return False 37 | 38 | def is_gesture_one(self, landmarks): 39 | index_tip = landmarks[8] 40 | middle_tip = landmarks[12] 41 | wrist = landmarks[0] 42 | return index_tip.y < wrist.y and middle_tip.y > wrist.y 43 | 44 | def is_gesture_two(self, landmarks): 45 | index_tip = landmarks[8] 46 | middle_tip = landmarks[12] 47 | ring_tip = landmarks[16] 48 | pinky_tip = landmarks[20] 49 | wrist = landmarks[0] 50 | return (index_tip.y < wrist.y and middle_tip.y < wrist.y and 51 | ring_tip.y > wrist.y and pinky_tip.y > wrist.y) 52 | 53 | def is_hand_open(self, landmarks): 54 | thumb_tip = landmarks[4] 55 | index_tip = landmarks[8] 56 | middle_tip = landmarks[12] 57 | ring_tip = landmarks[16] 58 | pinky_tip = landmarks[20] 59 | wrist = landmarks[0] 60 | return (thumb_tip.y < wrist.y and index_tip.y < wrist.y and 61 | middle_tip.y < wrist.y and ring_tip.y < wrist.y and pinky_tip.y < wrist.y) 62 | 63 | def reset(self): 64 | self.previous_flip_status = None 65 | self.flip_count = 0 66 | self.hand_open_detected = False # 重置五指张开状态 67 | self.hand_open_detected_time = 0 # 重置五指张开计时器 68 | self.gesture_two_detected_time = 0 # 重置手势2计时器 69 | 70 | 71 | # 机器人运动控制类 72 | class SportModeTest: 73 | def __init__(self) -> None: 74 | try: 75 | self.client = SportClient() 76 | self.client.SetTimeout(10.0) 77 | self.client.Init() 78 | except AttributeError as e: 79 | print(f"Error initializing SportClient: {e}") 80 | 81 | def RiseSit(self): 82 | try: 83 | self.client.RiseSit() 84 | print("Stand up !!!") 85 | except Exception as e: 86 | print(f"Error executing RiseSit: {e}") 87 | 88 | def Sit(self): 89 | try: 90 | self.client.Sit() 91 | print("Sit down !!!") 92 | except Exception as e: 93 | print(f"Error executing Sit: {e}") 94 | 95 | def Hello(self): 96 | try: 97 | self.client.Hello() 98 | print("Hello !!!") 99 | except Exception as e: 100 | print(f"Error executing Hello: {e}") 101 | 102 | def Heart(self): 103 | try: 104 | self.client.Heart() 105 | print("Heart !!!") 106 | except Exception as e: 107 | print(f"Error executing Heart: {e}") 108 | 109 | 110 | # 初始化视频客户端 111 | def initialize_video_client(network_interface): 112 | ChannelFactoryInitialize(0, network_interface) 113 | client = VideoClient() 114 | client.SetTimeout(3.0) 115 | client.Init() 116 | return client 117 | 118 | 119 | # 获取视频帧 120 | def get_video_frame(client): 121 | code, data = client.GetImageSample() 122 | if code == 0: 123 | image_data = np.frombuffer(bytes(data), dtype=np.uint8) 124 | image = cv2.imdecode(image_data, cv2.IMREAD_COLOR) 125 | return image 126 | else: 127 | print("Get image sample error. code:", code) 128 | return None 129 | 130 | 131 | # 绘制检测区域 132 | def draw_detection_area(image, radius): 133 | height, width, _ = image.shape 134 | center = (width // 2, (height // 2) - 200) 135 | mask = np.zeros((height, width), dtype=np.uint8) 136 | cv2.circle(mask, center, radius, 255, thickness=-1) 137 | cv2.circle(image, center, radius, (0, 255, 0), 2) 138 | return mask 139 | 140 | 141 | # 手势检测线程 142 | def gesture_detection_process(pipe, network_interface, last_action_time_shared): 143 | # 在子进程中重新初始化 144 | client = initialize_video_client(network_interface) 145 | mp_hands = mp_mediapipe.solutions.hands 146 | hands = mp_hands.Hands(min_detection_confidence=0.5, min_tracking_confidence=0.5) 147 | drawing_utils = mp_mediapipe.solutions.drawing_utils 148 | gesture_detector = HandGestureDetector() 149 | radius = 800 150 | 151 | gesture_last_sent = None # 保存上一次发送的手势指令 152 | 153 | while True: 154 | # 获取当前时间 155 | current_time = time.time() 156 | 157 | image = get_video_frame(client) 158 | if image is None: 159 | break 160 | 161 | mask = draw_detection_area(image, radius) 162 | imgRGB = cv2.cvtColor(image, cv2.COLOR_BGR2RGB) 163 | masked_image = cv2.bitwise_and(imgRGB, imgRGB, mask=mask) 164 | result = hands.process(masked_image) 165 | 166 | if result.multi_hand_landmarks: 167 | for handLms in result.multi_hand_landmarks: 168 | # 绘制手部关键点和骨骼 169 | drawing_utils.draw_landmarks(image, handLms, mp_hands.HAND_CONNECTIONS) 170 | 171 | # 打印检测到的手势 172 | print("Detected hand landmarks") 173 | 174 | # 检测五指张开 175 | if not gesture_detector.hand_open_detected: 176 | if gesture_detector.is_hand_open(handLms.landmark): 177 | gesture_detector.hand_open_detected = True 178 | gesture_detector.hand_open_detected_time = current_time # 记录五指张开时间 179 | print("Hand open detected, entering gesture detection mode") 180 | else: 181 | # 如果5秒内没有执行任何手势,重置 hand_open_detected 182 | if current_time - gesture_detector.hand_open_detected_time > 5: 183 | gesture_detector.reset() 184 | print("No actions detected within 5 seconds, resetting to hand open detection") 185 | continue 186 | 187 | # 检测手势1、手势2和翻转,仅在 hand_open_detected 为 True 时检测 188 | if gesture_detector.process_flip(handLms.landmark) and gesture_last_sent != "flip_detected": 189 | print("Flip detected") 190 | pipe.send("flip_detected") 191 | 192 | gesture_detector.hand_open_detected = False # 重置五指张开状态 193 | gesture_detector.hand_open_detected_time = 0 # 重置五指张开计时器 194 | 195 | gesture_last_sent = "flip_detected" 196 | elif gesture_detector.is_gesture_one(handLms.landmark) and gesture_last_sent != "gesture_one_detected": 197 | print("Gesture 1 detected") 198 | pipe.send("gesture_one_detected") 199 | 200 | gesture_detector.hand_open_detected = False # 重置五指张开状态 201 | gesture_detector.hand_open_detected_time = 0 # 重置五指张开计时器 202 | 203 | 204 | gesture_last_sent = "gesture_one_detected" 205 | elif gesture_detector.is_gesture_two(handLms.landmark) and gesture_last_sent != "gesture_two_detected": 206 | print("Gesture 2 detected") 207 | pipe.send("gesture_two_detected") 208 | 209 | gesture_detector.hand_open_detected = False # 重置五指张开状态 210 | gesture_detector.hand_open_detected_time = 0 # 重置五指张开计时器 211 | 212 | gesture_last_sent = "gesture_two_detected" 213 | else: 214 | gesture_last_sent = None # 如果没有手势,重置最后发送的手势 215 | 216 | # 显示视频流和手部骨骼 217 | cv2.imshow("front_camera", image) 218 | if cv2.waitKey(20) == 27: 219 | break 220 | 221 | cv2.destroyWindow("front_camera") 222 | 223 | 224 | # 机器人运动控制线程 225 | def robot_control_process(pipe, network_interface, last_action_time_shared): 226 | # 在子进程中重新初始化 227 | ChannelFactoryInitialize(0, network_interface) 228 | robot = SportModeTest() 229 | dog_is_standing = False 230 | 231 | while True: 232 | try: 233 | gesture = pipe.recv() # 等待接收手势指令 234 | print(f"Received gesture: {gesture}") 235 | 236 | # 不需要冷却时间,立即执行动作 237 | if gesture == "flip_detected": 238 | if dog_is_standing: 239 | robot.Sit() 240 | dog_is_standing = False 241 | else: 242 | robot.RiseSit() 243 | dog_is_standing = True 244 | 245 | elif gesture == "gesture_one_detected": 246 | robot.Hello() 247 | 248 | elif gesture == "gesture_two_detected": 249 | robot.Heart() 250 | 251 | except EOFError: 252 | break 253 | 254 | 255 | # 捕获信号处理,确保子进程能够优雅关闭 256 | def signal_handler(sig, frame): 257 | print("Signal received, terminating...") 258 | sys.exit(0) 259 | 260 | 261 | # 主函数 262 | def main(): 263 | # 捕获系统信号 (如 Ctrl+C) 并终止进程 264 | signal.signal(signal.SIGINT, signal_handler) 265 | signal.signal(signal.SIGTERM, signal_handler) 266 | 267 | parent_conn, child_conn = mp.Pipe() 268 | network_interface = sys.argv[1] # 获取网络接口 269 | 270 | # 创建一个共享的冷却时间变量 271 | last_action_time_shared = Value('d', time.time()) 272 | 273 | # 创建手势检测进程和机器人控制进程 274 | p1 = mp.Process(target=gesture_detection_process, args=(parent_conn, network_interface, last_action_time_shared)) 275 | p2 = mp.Process(target=robot_control_process, args=(child_conn, network_interface, last_action_time_shared)) 276 | 277 | p1.start() 278 | p2.start() 279 | 280 | try: 281 | p1.join() 282 | p2.join() 283 | except KeyboardInterrupt: 284 | print("KeyboardInterrupt caught, terminating processes...") 285 | finally: 286 | # 确保所有子进程被终止 287 | p1.terminate() 288 | p2.terminate() 289 | p1.join() 290 | p2.join() 291 | 292 | 293 | if __name__ == "__main__": 294 | main() 295 | --------------------------------------------------------------------------------