octv2_server.py 37 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919
  1. #!/usr/bin/env python3
  2. """
  3. OCTv2 (Oreo Cookie Thrower v2) - Raspberry Pi Server v2
  4. - ESP32 serial communication for motor control
  5. - Automatic mouth detection and targeting
  6. - Stepper motor control for rotation and pitch
  7. """
  8. import socket
  9. import json
  10. import threading
  11. import time
  12. import logging
  13. import serial
  14. import cv2
  15. import numpy as np
  16. from datetime import datetime
  17. from typing import Dict, Any, Optional, Tuple, List
  18. import io
  19. import os
  20. import math
  21. # Camera imports
  22. try:
  23. from picamera2 import Picamera2
  24. CAMERA_AVAILABLE = True
  25. except ImportError:
  26. print("Camera not available - running in simulation mode")
  27. CAMERA_AVAILABLE = False
  28. # Configure logging
  29. logging.basicConfig(
  30. level=logging.INFO,
  31. format='%(asctime)s - %(levelname)s - %(message)s'
  32. )
  33. logger = logging.getLogger(__name__)
  34. class ESP32Controller:
  35. """Handle serial communication with ESP32 for motor control"""
  36. def __init__(self, port='/dev/ttyUSB0', baudrate=115200):
  37. self.port = port
  38. self.baudrate = baudrate
  39. self.serial_conn = None
  40. self.connect()
  41. def connect(self):
  42. """Connect to ESP32 via serial with infinite retry"""
  43. retry_delay = 2.0
  44. attempt = 0
  45. logger.info("ESP32 connection required - will retry indefinitely...")
  46. while True:
  47. attempt += 1
  48. try:
  49. self.serial_conn = serial.Serial(self.port, self.baudrate, timeout=1)
  50. time.sleep(2) # Wait for ESP32 to initialize
  51. # Test connection with a simple command
  52. test_response = self.send_command("STATUS")
  53. if "ERROR" not in test_response:
  54. logger.info(f"✅ Connected to ESP32 on {self.port} (attempt {attempt})")
  55. return True
  56. else:
  57. self.serial_conn.close()
  58. self.serial_conn = None
  59. except Exception as e:
  60. logger.warning(f"ESP32 connection attempt {attempt} failed: {e}")
  61. if self.serial_conn:
  62. self.serial_conn.close()
  63. self.serial_conn = None
  64. logger.info(f"Retrying ESP32 connection in {retry_delay} seconds...")
  65. time.sleep(retry_delay)
  66. def send_command(self, command: str) -> str:
  67. """Send command to ESP32 and get response"""
  68. if not self.serial_conn:
  69. logger.error("ESP32 not connected")
  70. return "ERROR: Not connected"
  71. try:
  72. self.serial_conn.write(f"{command}\n".encode())
  73. response = self.serial_conn.readline().decode().strip()
  74. logger.debug(f"ESP32 Command: {command} -> Response: {response}")
  75. return response
  76. except Exception as e:
  77. logger.error(f"ESP32 communication error: {e}")
  78. return "ERROR: Communication failed"
  79. def home_motors(self) -> bool:
  80. """Home both rotation and pitch motors"""
  81. response = self.send_command("HOME")
  82. return response == "OK"
  83. def move_to_position(self, rotation_degrees: float, pitch_degrees: float) -> bool:
  84. """Move to absolute position (rotation: -90 to +90, pitch: 0 to 60)"""
  85. cmd = f"MOVE {rotation_degrees:.1f} {pitch_degrees:.1f}"
  86. response = self.send_command(cmd)
  87. return response == "OK"
  88. def move_relative(self, delta_rotation: float, delta_pitch: float) -> bool:
  89. """Move relative to current position"""
  90. cmd = f"REL {delta_rotation:.1f} {delta_pitch:.1f}"
  91. response = self.send_command(cmd)
  92. return response == "OK"
  93. def fire_oreo(self) -> bool:
  94. """Trigger the firing mechanism"""
  95. response = self.send_command("FIRE")
  96. return response == "OK"
  97. def get_position(self) -> Tuple[float, float]:
  98. """Get current position (rotation, pitch)"""
  99. response = self.send_command("POS")
  100. try:
  101. parts = response.split()
  102. if len(parts) == 2:
  103. return float(parts[0]), float(parts[1])
  104. except:
  105. pass
  106. return 0.0, 0.0
  107. class MouthDetector:
  108. """Detect open mouths in camera feed for automatic targeting"""
  109. def __init__(self):
  110. # Load OpenCV face cascade classifier
  111. self.face_cascade = cv2.CascadeClassifier(cv2.data.haarcascades + 'haarcascade_frontalface_default.xml')
  112. # For actual open mouth detection, we'll use facial landmarks
  113. try:
  114. import dlib
  115. # Download shape predictor: http://dlib.net/files/shape_predictor_68_face_landmarks.dat.bz2
  116. self.predictor = dlib.shape_predictor("shape_predictor_68_face_landmarks.dat")
  117. self.detector = dlib.get_frontal_face_detector()
  118. self.use_dlib = True
  119. logger.info("Using dlib for precise mouth detection")
  120. except ImportError:
  121. logger.warning("dlib not available - using basic mouth area detection")
  122. self.use_dlib = False
  123. # Camera parameters for targeting calculations
  124. self.camera_width = 640
  125. self.camera_height = 480
  126. self.center_x = self.camera_width // 2
  127. self.center_y = self.camera_height // 2
  128. # Camera-follows-aim targeting parameters
  129. self.target_deadzone_pixels = 30 # Don't adjust if mouth is within this radius of center
  130. self.max_adjustment_degrees = 10 # Maximum single adjustment per iteration
  131. # Distance estimation parameters (based on average human face size)
  132. self.average_face_width_cm = 16.0 # Average human face width
  133. self.camera_focal_length_mm = 3.04 # Pi Camera focal length
  134. self.sensor_width_mm = 3.68 # Pi Camera sensor width
  135. # Aiming offsets (configurable for mechanical compensation)
  136. self.rotation_offset_degrees = 0.0 # Adjust if camera/launcher not perfectly aligned
  137. self.pitch_offset_degrees = 0.0 # Adjust for gravity compensation
  138. self.distance_pitch_factor = 0.5 # Elevation adjustment based on distance
  139. logger.info("Mouth detector initialized")
  140. def detect_open_mouths(self, frame) -> List[Tuple[int, int, int, int, float]]:
  141. """
  142. Detect open mouths in frame
  143. Returns list of (x, y, w, h, confidence) for each detected mouth
  144. """
  145. gray = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY)
  146. mouths = []
  147. if self.use_dlib:
  148. # Use dlib for precise facial landmark detection
  149. faces = self.detector(gray)
  150. for face in faces:
  151. landmarks = self.predictor(gray, face)
  152. # Get mouth landmarks (points 48-67 in 68-point model)
  153. mouth_points = []
  154. for i in range(48, 68):
  155. point = landmarks.part(i)
  156. mouth_points.append((point.x, point.y))
  157. # Advanced mouth analysis for WIDE-OPEN detection only
  158. mouth_state, confidence = self._analyze_mouth_state(landmarks)
  159. # Only target WIDE_OPEN mouths (not speaking or smiling)
  160. if mouth_state == "WIDE_OPEN":
  161. # Calculate bounding box around mouth
  162. mouth_xs = [p[0] for p in mouth_points]
  163. mouth_ys = [p[1] for p in mouth_points]
  164. mx = min(mouth_xs) - 10
  165. my = min(mouth_ys) - 10
  166. mw = max(mouth_xs) - min(mouth_xs) + 20
  167. mh = max(mouth_ys) - min(mouth_ys) + 20
  168. mouths.append((mx, my, mw, mh, confidence))
  169. else:
  170. # Fallback to basic face detection + mouth area estimation
  171. faces = self.face_cascade.detectMultiScale(gray, 1.3, 5)
  172. for (fx, fy, fw, fh) in faces:
  173. # Estimate mouth area in lower third of face
  174. mouth_x = fx + int(fw * 0.25)
  175. mouth_y = fy + int(fh * 0.6)
  176. mouth_w = int(fw * 0.5)
  177. mouth_h = int(fh * 0.3)
  178. # Use intensity variance as proxy for open mouth
  179. mouth_roi = gray[mouth_y:mouth_y+mouth_h, mouth_x:mouth_x+mouth_w]
  180. if mouth_roi.size > 0:
  181. variance = np.var(mouth_roi)
  182. # Higher variance might indicate teeth/tongue visibility
  183. confidence = min(1.0, variance / 1000.0) # Adjust threshold
  184. if confidence > 0.3: # Minimum confidence threshold
  185. mouths.append((mouth_x, mouth_y, mouth_w, mouth_h, confidence))
  186. # Sort by confidence (highest first)
  187. mouths.sort(key=lambda x: x[4], reverse=True)
  188. return mouths
  189. def _analyze_mouth_state(self, landmarks) -> Tuple[str, float]:
  190. """
  191. Analyze mouth landmarks to determine state and confidence
  192. Uses 68-point facial landmark model where mouth points are 48-67:
  193. - Points 48-54: Outer lip contour (left to right)
  194. - Points 55-59: Outer lip contour (right to left)
  195. - Points 60-64: Inner lip contour (left to right)
  196. - Points 65-67: Inner lip contour (right to left)
  197. Algorithm:
  198. 1. Calculate mouth aspect ratios (height/width) for inner and outer lips
  199. 2. Measure lip separation (distance between inner lip points)
  200. 3. Classify based on thresholds tuned for WIDE_OPEN detection
  201. 4. Only WIDE_OPEN mouths are targeted for firing
  202. Returns: (state, confidence) where state is CLOSED, SPEAKING, SMILING, or WIDE_OPEN
  203. """
  204. # Key mouth landmark points
  205. # Outer lip: 48-54 (top), 54-60 (bottom)
  206. # Inner lip: 60-64 (top), 64-68 (bottom)
  207. # Vertical measurements (mouth opening)
  208. outer_top = landmarks.part(51) # Top of upper lip (center)
  209. outer_bottom = landmarks.part(57) # Bottom of lower lip (center)
  210. inner_top = landmarks.part(62) # Top of inner lip
  211. inner_bottom = landmarks.part(66) # Bottom of inner lip
  212. # Horizontal measurements (mouth width)
  213. left_corner = landmarks.part(48) # Left mouth corner
  214. right_corner = landmarks.part(54) # Right mouth corner
  215. # Calculate dimensions
  216. outer_height = abs(outer_top.y - outer_bottom.y)
  217. inner_height = abs(inner_top.y - inner_bottom.y)
  218. mouth_width = abs(right_corner.x - left_corner.x)
  219. # Calculate ratios
  220. outer_aspect_ratio = outer_height / mouth_width if mouth_width > 0 else 0
  221. inner_aspect_ratio = inner_height / mouth_width if mouth_width > 0 else 0
  222. # Calculate lip separation (distance between inner and outer lip)
  223. lip_thickness_top = abs(outer_top.y - inner_top.y)
  224. lip_thickness_bottom = abs(outer_bottom.y - inner_bottom.y)
  225. avg_lip_thickness = (lip_thickness_top + lip_thickness_bottom) / 2
  226. # Determine mouth state based on multiple criteria
  227. # WIDE_OPEN: Large inner opening + significant lip separation
  228. if (inner_aspect_ratio > 0.6 and
  229. outer_aspect_ratio > 0.4 and
  230. avg_lip_thickness > 8): # Pixels of lip separation
  231. confidence = min(1.0, inner_aspect_ratio * 1.5)
  232. return "WIDE_OPEN", confidence
  233. # SPEAKING: Moderate opening but less lip separation
  234. elif (inner_aspect_ratio > 0.3 and
  235. outer_aspect_ratio > 0.2 and
  236. avg_lip_thickness > 3):
  237. confidence = min(1.0, inner_aspect_ratio * 0.8)
  238. return "SPEAKING", confidence
  239. # SMILING: Wide mouth but minimal vertical opening
  240. elif (mouth_width > 40 and # Wider than normal
  241. outer_aspect_ratio < 0.25 and
  242. inner_aspect_ratio < 0.2):
  243. # Check if corners are raised (smile detection)
  244. mouth_center_y = (outer_top.y + outer_bottom.y) / 2
  245. corner_raise = mouth_center_y - ((left_corner.y + right_corner.y) / 2)
  246. if corner_raise > 3: # Corners raised above center
  247. return "SMILING", 0.3
  248. # Default: CLOSED
  249. return "CLOSED", 0.1
  250. def estimate_distance(self, face_width_pixels: int) -> float:
  251. """
  252. Estimate distance to face based on face width in pixels
  253. Returns distance in centimeters
  254. """
  255. if face_width_pixels <= 0:
  256. return 100.0 # Default fallback distance
  257. # Distance = (real_face_width * focal_length * image_width) / (face_width_pixels * sensor_width)
  258. distance_cm = (
  259. self.average_face_width_cm *
  260. self.camera_focal_length_mm *
  261. self.camera_width
  262. ) / (face_width_pixels * self.sensor_width_mm)
  263. # Clamp to reasonable range (50cm to 500cm)
  264. return max(50.0, min(500.0, distance_cm))
  265. def calculate_centering_adjustment(self, mouth_x: int, mouth_y: int, face_width: int) -> Tuple[float, float, float]:
  266. """
  267. Calculate motor adjustments to center the mouth in camera view
  268. Camera-follows-aim targeting algorithm:
  269. 1. Calculate pixel offset from mouth center to camera center
  270. 2. Convert pixels to degrees using calibrated conversion factors
  271. 3. Apply distance scaling (closer targets need smaller adjustments)
  272. 4. Add mechanical offset compensation
  273. 5. Add distance-based pitch compensation for projectile trajectory
  274. Args:
  275. mouth_x, mouth_y: Center coordinates of detected mouth in pixels
  276. face_width: Width of face in pixels (for distance estimation)
  277. Returns:
  278. (rotation_adjustment, pitch_adjustment, estimated_distance)
  279. - rotation_adjustment: Horizontal angle change in degrees (-90 to +90)
  280. - pitch_adjustment: Vertical angle change in degrees (0 to 60)
  281. - estimated_distance: Distance to target in cm
  282. """
  283. # Calculate offset from center
  284. dx = mouth_x - self.center_x
  285. dy = mouth_y - self.center_y
  286. distance_from_center = math.sqrt(dx*dx + dy*dy)
  287. # Estimate distance for context
  288. estimated_distance = self.estimate_distance(face_width)
  289. # If mouth is already centered (within deadzone), no adjustment needed
  290. if distance_from_center < self.target_deadzone_pixels:
  291. return 0.0, 0.0, estimated_distance
  292. # Calculate adjustment angles based on pixel offset
  293. # Larger faces (closer) need smaller adjustments, smaller faces (farther) need larger adjustments
  294. distance_factor = max(0.5, min(2.0, 100.0 / estimated_distance)) # Scale adjustments by distance
  295. # Convert pixel offset to approximate angle adjustment
  296. # This is empirical - you'll need to tune these values for your setup
  297. pixels_per_degree_rotation = 15 * distance_factor # Adjust based on your camera/motor setup
  298. pixels_per_degree_pitch = 12 * distance_factor # Adjust based on your camera/motor setup
  299. rotation_adjustment = dx / pixels_per_degree_rotation
  300. pitch_adjustment = -dy / pixels_per_degree_pitch # Negative because Y increases downward
  301. # Apply configured offsets
  302. rotation_adjustment += self.rotation_offset_degrees
  303. pitch_adjustment += self.pitch_offset_degrees
  304. # Add distance-based pitch compensation (closer targets need higher pitch)
  305. distance_pitch_compensation = (200.0 - estimated_distance) * self.distance_pitch_factor / 100.0
  306. pitch_adjustment += distance_pitch_compensation
  307. # Clamp to maximum adjustment per iteration
  308. rotation_adjustment = max(-self.max_adjustment_degrees,
  309. min(self.max_adjustment_degrees, rotation_adjustment))
  310. pitch_adjustment = max(-self.max_adjustment_degrees,
  311. min(self.max_adjustment_degrees, pitch_adjustment))
  312. return rotation_adjustment, pitch_adjustment, estimated_distance
  313. class OCTv2Server:
  314. """
  315. Main OCTv2 server handling iOS app communication and hardware control
  316. Architecture:
  317. - TCP server for iOS app communication (JSON protocol)
  318. - ESP32 serial communication for motor control
  319. - Computer vision for automatic mouth detection and targeting
  320. - Camera streaming with detection overlays
  321. """
  322. def __init__(self, host='0.0.0.0', port=8080):
  323. self.host = host
  324. self.port = port
  325. self.running = False
  326. self.clients = []
  327. # Initialize ESP32 controller (required - will block until connected)
  328. logger.info("Initializing ESP32 controller...")
  329. self.esp32 = ESP32Controller()
  330. try:
  331. self.mouth_detector = MouthDetector()
  332. except Exception as e:
  333. logger.error(f"Failed to initialize mouth detector: {e}")
  334. self.mouth_detector = None
  335. # Hardware state
  336. self.current_rotation = 0.0 # -90 to +90 degrees
  337. self.current_pitch = 30.0 # 0 to 60 degrees
  338. self.is_auto_mode = False
  339. self.is_homed = False
  340. self.auto_fire_enabled = True
  341. # Camera state
  342. self.camera = None
  343. self.streaming_clients = []
  344. self.stream_thread = None
  345. # Auto mode state
  346. self.auto_mode_thread = None
  347. self.last_target_time = 0
  348. self.target_cooldown = 2.0 # Seconds between automatic shots
  349. self.setup_camera()
  350. def setup_camera(self):
  351. """Initialize camera with error handling and fallback options"""
  352. if not CAMERA_AVAILABLE:
  353. logger.warning("Picamera2 not available - running in simulation mode")
  354. logger.info("Install with: sudo apt install python3-picamera2")
  355. return
  356. max_retries = 3
  357. for attempt in range(max_retries):
  358. try:
  359. self.camera = Picamera2()
  360. # Configure camera with optimal settings for mouth detection
  361. config = self.camera.create_preview_configuration(
  362. main={"size": (640, 480)}, # Good resolution for detection
  363. lores={"size": (320, 240)}, # Lower res for streaming
  364. display="lores"
  365. )
  366. self.camera.configure(config)
  367. self.camera.start()
  368. # Test camera by capturing a frame
  369. test_frame = self.camera.capture_array()
  370. if test_frame is not None and test_frame.size > 0:
  371. logger.info(f"Camera initialized successfully (attempt {attempt + 1})")
  372. return True
  373. except Exception as e:
  374. logger.warning(f"Camera initialization attempt {attempt + 1} failed: {e}")
  375. if self.camera:
  376. try:
  377. self.camera.stop()
  378. except:
  379. pass
  380. self.camera = None
  381. if attempt < max_retries - 1:
  382. time.sleep(1)
  383. logger.error(f"Failed to initialize camera after {max_retries} attempts")
  384. logger.info("System will run without camera functionality")
  385. return False
  386. def start_server(self):
  387. """Start the TCP server"""
  388. self.running = True
  389. server_socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
  390. server_socket.setsockopt(socket.SOL_SOCKET, socket.SO_REUSEADDR, 1)
  391. try:
  392. server_socket.bind((self.host, self.port))
  393. server_socket.listen(5)
  394. logger.info(f"OCTv2 Server v2 listening on {self.host}:{self.port}")
  395. # Start auto mode thread
  396. self.auto_mode_thread = threading.Thread(target=self.auto_mode_worker)
  397. self.auto_mode_thread.daemon = True
  398. self.auto_mode_thread.start()
  399. while self.running:
  400. try:
  401. client_socket, address = server_socket.accept()
  402. logger.info(f"Client connected from {address}")
  403. client_thread = threading.Thread(
  404. target=self.handle_client,
  405. args=(client_socket, address)
  406. )
  407. client_thread.daemon = True
  408. client_thread.start()
  409. except Exception as e:
  410. if self.running:
  411. logger.error(f"Error accepting client: {e}")
  412. except Exception as e:
  413. logger.error(f"Server error: {e}")
  414. finally:
  415. server_socket.close()
  416. self.cleanup()
  417. def handle_client(self, client_socket, address):
  418. """Handle individual client connections"""
  419. self.clients.append(client_socket)
  420. try:
  421. while self.running:
  422. data = client_socket.recv(1024)
  423. if not data:
  424. break
  425. try:
  426. command = json.loads(data.decode('utf-8'))
  427. logger.info(f"Received command: {command}")
  428. response = self.process_command(command, client_socket)
  429. if response:
  430. client_socket.send(json.dumps(response).encode('utf-8'))
  431. except json.JSONDecodeError:
  432. logger.error("Invalid JSON received")
  433. except Exception as e:
  434. logger.error(f"Error processing command: {e}")
  435. except Exception as e:
  436. logger.error(f"Client {address} error: {e}")
  437. finally:
  438. if client_socket in self.clients:
  439. self.clients.remove(client_socket)
  440. if client_socket in self.streaming_clients:
  441. self.streaming_clients.remove(client_socket)
  442. client_socket.close()
  443. logger.info(f"Client {address} disconnected")
  444. def process_command(self, command: Dict[str, Any], client_socket) -> Optional[Dict[str, Any]]:
  445. """Process commands from iOS app"""
  446. action = command.get('action')
  447. logger.info(f"Processing action: {action}")
  448. if action == 'aim_left':
  449. return self.aim_left()
  450. elif action == 'aim_right':
  451. return self.aim_right()
  452. elif action == 'fire':
  453. angle = command.get('angle', self.current_pitch)
  454. return self.fire_oreo(angle)
  455. elif action == 'home':
  456. return self.home_device()
  457. elif action == 'set_mode':
  458. mode = command.get('mode', 'manual')
  459. return self.set_mode(mode)
  460. elif action == 'capture_photo':
  461. return self.capture_photo(client_socket)
  462. elif action == 'start_video_stream':
  463. return self.start_video_stream(client_socket)
  464. elif action == 'stop_video_stream':
  465. return self.stop_video_stream(client_socket)
  466. elif action == 'status':
  467. return self.get_status()
  468. else:
  469. return {'error': f'Unknown action: {action}'}
  470. def aim_left(self) -> Dict[str, Any]:
  471. """Move aim left by small increment"""
  472. new_rotation = max(-90, self.current_rotation - 5)
  473. if self.esp32.move_to_position(new_rotation, self.current_pitch):
  474. self.current_rotation = new_rotation
  475. return {'status': 'success', 'rotation': self.current_rotation}
  476. return {'status': 'error', 'message': 'Failed to move left'}
  477. def aim_right(self) -> Dict[str, Any]:
  478. """Move aim right by small increment"""
  479. new_rotation = min(90, self.current_rotation + 5)
  480. if self.esp32.move_to_position(new_rotation, self.current_pitch):
  481. self.current_rotation = new_rotation
  482. return {'status': 'success', 'rotation': self.current_rotation}
  483. return {'status': 'error', 'message': 'Failed to move right'}
  484. def fire_oreo(self, pitch: float = None) -> Dict[str, Any]:
  485. """Fire an Oreo at the specified pitch"""
  486. if pitch is not None:
  487. # Move to target pitch first
  488. self.current_pitch = max(0, min(60, pitch))
  489. if not self.esp32.move_to_position(self.current_rotation, self.current_pitch):
  490. return {'status': 'error', 'message': 'Failed to move to position'}
  491. time.sleep(0.5) # Wait for positioning
  492. logger.info(f"FIRING OREO at rotation={self.current_rotation}°, pitch={self.current_pitch}°!")
  493. if self.esp32.fire_oreo():
  494. return {
  495. 'status': 'success',
  496. 'message': f'Oreo fired at R:{self.current_rotation}° E:{self.current_pitch}°',
  497. 'rotation': self.current_rotation,
  498. 'pitch': self.current_pitch
  499. }
  500. else:
  501. return {'status': 'error', 'message': 'Fire mechanism failed'}
  502. def home_device(self) -> Dict[str, Any]:
  503. """Home the device to its reference position"""
  504. logger.info("Homing device...")
  505. if self.esp32.home_motors():
  506. self.current_rotation = 0.0
  507. self.current_pitch = 0.0
  508. self.is_homed = True
  509. return {
  510. 'status': 'success',
  511. 'message': 'Device homed successfully',
  512. 'rotation': 0,
  513. 'pitch': 0
  514. }
  515. else:
  516. return {'status': 'error', 'message': 'Homing failed'}
  517. def set_mode(self, mode: str) -> Dict[str, Any]:
  518. """Set operating mode (auto/manual)"""
  519. self.is_auto_mode = (mode.lower() == 'auto')
  520. logger.info(f"Mode set to: {mode}")
  521. if self.is_auto_mode:
  522. logger.info("🎯 AUTOMATIC MODE ENABLED - Seeking open mouths!")
  523. else:
  524. logger.info("🎮 Manual mode enabled")
  525. return {
  526. 'status': 'success',
  527. 'mode': mode,
  528. 'auto_mode': self.is_auto_mode
  529. }
  530. def auto_mode_worker(self):
  531. """Worker thread for automatic mouth detection and firing"""
  532. while self.running:
  533. try:
  534. if self.is_auto_mode and CAMERA_AVAILABLE and self.camera:
  535. # Capture frame for analysis
  536. frame = self.camera.capture_array()
  537. # Detect open mouths
  538. mouths = self.mouth_detector.detect_open_mouths(frame)
  539. if mouths and self.auto_fire_enabled:
  540. current_time = time.time()
  541. if current_time - self.last_target_time > self.target_cooldown:
  542. # Target the most confident mouth
  543. best_mouth = mouths[0]
  544. mx, my, mw, mh, confidence = best_mouth
  545. # Calculate mouth center and face width (estimate from mouth width)
  546. mouth_center_x = mx + mw // 2
  547. mouth_center_y = my + mh // 2
  548. estimated_face_width = int(mw * 2.5) # Face is roughly 2.5x wider than mouth
  549. # Calculate centering adjustment
  550. rotation_adj, pitch_adj, distance = self.mouth_detector.calculate_centering_adjustment(
  551. mouth_center_x, mouth_center_y, estimated_face_width
  552. )
  553. logger.info(f"🎯 AUTO TARGET: Mouth detected (confidence {confidence:.2f}, distance ~{distance:.0f}cm)")
  554. # Only adjust if mouth is not already centered
  555. if abs(rotation_adj) > 0.1 or abs(pitch_adj) > 0.1:
  556. # Calculate new position with adjustments
  557. new_rotation = max(-90, min(90, self.current_rotation + rotation_adj))
  558. new_pitch = max(0, min(60, self.current_pitch + pitch_adj))
  559. logger.info(f"🎯 CENTERING: Adjusting R:{rotation_adj:+.1f}° E:{pitch_adj:+.1f}° -> R:{new_rotation:.1f}° E:{new_pitch:.1f}°")
  560. # Move to center the target
  561. if self.esp32.move_to_position(new_rotation, new_pitch):
  562. self.current_rotation = new_rotation
  563. self.current_pitch = new_pitch
  564. time.sleep(0.5) # Wait for positioning
  565. else:
  566. logger.info("🎯 TARGET CENTERED: Mouth already in optimal position")
  567. # Check if mouth is now well-centered for firing
  568. dx = mouth_center_x - self.mouth_detector.center_x
  569. dy = mouth_center_y - self.mouth_detector.center_y
  570. center_distance = math.sqrt(dx*dx + dy*dy)
  571. if center_distance < self.mouth_detector.target_deadzone_pixels * 1.5: # Allow some tolerance
  572. # Fire!
  573. logger.info(f"🔥 AUTO FIRE: Launching Oreo at centered target! (offset: {center_distance:.0f}px)")
  574. self.esp32.fire_oreo()
  575. self.last_target_time = current_time
  576. else:
  577. logger.info(f"🎯 TARGET NOT CENTERED: Waiting for better positioning (offset: {center_distance:.0f}px)")
  578. time.sleep(0.1) # Check at ~10fps
  579. except Exception as e:
  580. logger.error(f"Auto mode error: {e}")
  581. time.sleep(1)
  582. def capture_photo(self, client_socket) -> Dict[str, Any]:
  583. """Capture a high-resolution photo"""
  584. if not CAMERA_AVAILABLE:
  585. logger.info("SIMULATED: Photo captured")
  586. return {'status': 'success', 'message': 'Photo captured (simulated)'}
  587. try:
  588. timestamp = datetime.now().strftime("%Y%m%d_%H%M%S")
  589. filename = f"octv2_photo_{timestamp}.jpg"
  590. self.camera.capture_file(filename)
  591. # Send photo back to app
  592. with open(filename, 'rb') as f:
  593. photo_data = f.read()
  594. client_socket.send(photo_data)
  595. return {
  596. 'status': 'success',
  597. 'filename': filename,
  598. 'message': 'Photo captured and saved'
  599. }
  600. except Exception as e:
  601. logger.error(f"Photo capture failed: {e}")
  602. return {'status': 'error', 'message': str(e)}
  603. def start_video_stream(self, client_socket) -> Dict[str, Any]:
  604. """Start video streaming to client"""
  605. if client_socket not in self.streaming_clients:
  606. self.streaming_clients.append(client_socket)
  607. if not self.stream_thread or not self.stream_thread.is_alive():
  608. self.stream_thread = threading.Thread(target=self.video_stream_worker)
  609. self.stream_thread.daemon = True
  610. self.stream_thread.start()
  611. return {'status': 'success', 'message': 'Video stream started'}
  612. def stop_video_stream(self, client_socket) -> Dict[str, Any]:
  613. """Stop video streaming to client"""
  614. if client_socket in self.streaming_clients:
  615. self.streaming_clients.remove(client_socket)
  616. return {'status': 'success', 'message': 'Video stream stopped'}
  617. def video_stream_worker(self):
  618. """Worker thread for video streaming with mouth detection overlay"""
  619. if not CAMERA_AVAILABLE:
  620. logger.info("SIMULATED: Video streaming started")
  621. return
  622. try:
  623. while self.streaming_clients:
  624. # Capture frame
  625. frame = self.camera.capture_array()
  626. # Add mouth detection overlay in auto mode
  627. if self.is_auto_mode:
  628. mouths = self.mouth_detector.detect_open_mouths(frame)
  629. self._add_mouth_detection_overlay(frame, mouths)
  630. # Draw targeting crosshair and deadzone
  631. center_x, center_y = frame.shape[1] // 2, frame.shape[0] // 2
  632. deadzone = self.mouth_detector.target_deadzone_pixels
  633. # Main crosshair
  634. cv2.line(frame, (center_x-20, center_y), (center_x+20, center_y), (255, 0, 0), 2)
  635. cv2.line(frame, (center_x, center_y-20), (center_x, center_y+20), (255, 0, 0), 2)
  636. # Deadzone circle
  637. cv2.circle(frame, (center_x, center_y), deadzone, (255, 0, 0), 2)
  638. cv2.putText(frame, 'TARGET ZONE', (center_x-50, center_y+deadzone+20),
  639. cv2.FONT_HERSHEY_SIMPLEX, 0.5, (255, 0, 0), 2)
  640. # Convert to JPEG
  641. _, jpeg = cv2.imencode('.jpg', frame)
  642. frame_data = jpeg.tobytes()
  643. # Send to all streaming clients
  644. for client in self.streaming_clients[:]:
  645. try:
  646. client.send(frame_data)
  647. except Exception as e:
  648. logger.error(f"Failed to send frame to client: {e}")
  649. self.streaming_clients.remove(client)
  650. time.sleep(0.1) # ~10 FPS
  651. except Exception as e:
  652. logger.error(f"Video streaming error: {e}")
  653. def get_status(self) -> Dict[str, Any]:
  654. """Return current device status"""
  655. # Get actual position from ESP32
  656. actual_rotation, actual_pitch = self.esp32.get_position()
  657. return {
  658. 'status': 'success',
  659. 'rotation': actual_rotation,
  660. 'pitch': actual_pitch,
  661. 'auto_mode': self.is_auto_mode,
  662. 'homed': self.is_homed,
  663. 'streaming_clients': len(self.streaming_clients),
  664. 'total_clients': len(self.clients),
  665. 'esp32_connected': self.esp32.serial_conn is not None
  666. }
  667. def cleanup(self):
  668. """Clean up resources"""
  669. self.running = False
  670. if self.camera and CAMERA_AVAILABLE:
  671. self.camera.stop()
  672. if self.esp32.serial_conn:
  673. self.esp32.serial_conn.close()
  674. logger.info("Server shutdown complete")
  675. def _add_mouth_detection_overlay(self, frame, mouths):
  676. """Add visual overlay showing mouth detection results"""
  677. if not self.mouth_detector.use_dlib:
  678. # Simple overlay for basic detection
  679. for mx, my, mw, mh, confidence in mouths:
  680. color = (0, 255, 0) if confidence > 0.5 else (0, 255, 255)
  681. cv2.rectangle(frame, (mx, my), (mx + mw, my + mh), color, 2)
  682. cv2.putText(frame, f'{confidence:.2f}', (mx, my-10),
  683. cv2.FONT_HERSHEY_SIMPLEX, 0.6, color, 2)
  684. return
  685. # Advanced overlay showing all mouth states
  686. gray = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY)
  687. faces = self.mouth_detector.detector(gray)
  688. for face in faces:
  689. landmarks = self.mouth_detector.predictor(gray, face)
  690. mouth_state, confidence = self.mouth_detector._analyze_mouth_state(landmarks)
  691. # Get face bounding box
  692. x1, y1, x2, y2 = face.left(), face.top(), face.right(), face.bottom()
  693. # Color coding for different states
  694. state_colors = {
  695. "WIDE_OPEN": (0, 255, 0), # Bright green - TARGET!
  696. "SPEAKING": (0, 165, 255), # Orange
  697. "SMILING": (255, 255, 0), # Cyan
  698. "CLOSED": (128, 128, 128) # Gray
  699. }
  700. color = state_colors.get(mouth_state, (128, 128, 128))
  701. # Draw face rectangle
  702. if mouth_state == "WIDE_OPEN":
  703. # Thick border for targets
  704. cv2.rectangle(frame, (x1, y1), (x2, y2), color, 4)
  705. # Add target indicator
  706. cv2.putText(frame, "🎯 TARGET!", (x1, y1-40),
  707. cv2.FONT_HERSHEY_SIMPLEX, 0.8, color, 2)
  708. else:
  709. # Thin border for non-targets
  710. cv2.rectangle(frame, (x1, y1), (x2, y2), color, 2)
  711. # Show mouth state, confidence, and distance
  712. cv2.putText(frame, f'{mouth_state}', (x1, y1-20),
  713. cv2.FONT_HERSHEY_SIMPLEX, 0.6, color, 2)
  714. cv2.putText(frame, f'{confidence:.2f}', (x1, y2+20),
  715. cv2.FONT_HERSHEY_SIMPLEX, 0.5, color, 2)
  716. # Add distance estimation for WIDE_OPEN mouths
  717. if mouth_state == "WIDE_OPEN":
  718. face_width = x2 - x1
  719. distance = self.mouth_detector.estimate_distance(face_width)
  720. cv2.putText(frame, f'~{distance:.0f}cm', (x1, y2+40),
  721. cv2.FONT_HERSHEY_SIMPLEX, 0.5, color, 2)
  722. # Draw mouth landmarks for WIDE_OPEN targets
  723. if mouth_state == "WIDE_OPEN":
  724. # Draw mouth contour
  725. mouth_points = []
  726. for i in range(48, 68):
  727. point = landmarks.part(i)
  728. mouth_points.append((point.x, point.y))
  729. if i in [48, 54, 62, 66]: # Key points
  730. cv2.circle(frame, (point.x, point.y), 3, (0, 255, 0), -1)
  731. # Draw mouth outline
  732. mouth_points = np.array(mouth_points, dtype=np.int32)
  733. cv2.polylines(frame, [mouth_points], True, (0, 255, 0), 2)
  734. # Add detection stats
  735. total_faces = len(faces)
  736. wide_open_count = len([m for m in mouths if len(m) > 4]) # mouths from detect_open_mouths only contain WIDE_OPEN
  737. cv2.putText(frame, f'Faces: {total_faces}', (10, 30),
  738. cv2.FONT_HERSHEY_SIMPLEX, 0.7, (255, 255, 255), 2)
  739. cv2.putText(frame, f'Targets: {wide_open_count}', (10, 60),
  740. cv2.FONT_HERSHEY_SIMPLEX, 0.7, (0, 255, 0), 2)
  741. def main():
  742. """Main entry point"""
  743. print("🍪 OCTv2 (Oreo Cookie Thrower v2) Server v2 Starting...")
  744. print("🤖 Features: ESP32 Control + Automatic Mouth Detection")
  745. server = OCTv2Server()
  746. try:
  747. server.start_server()
  748. except KeyboardInterrupt:
  749. print("\n🛑 Shutting down OCTv2 server...")
  750. server.cleanup()
  751. if __name__ == "__main__":
  752. main()