ptz_camera.py 20 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595
  1. """
  2. 球机(PTZ)控制模块
  3. 负责PTZ控制、精确定位和视频流获取
  4. """
  5. import os
  6. # 必须在导入cv2之前设置,防止FFmpeg多线程解码崩溃
  7. os.environ['OPENCV_FFMPEG_CAPTURE_OPTIONS'] = 'rtsp_transport;tcp|threads;1'
  8. import math
  9. import time
  10. import threading
  11. import queue
  12. from typing import Optional, Tuple, Dict
  13. from dataclasses import dataclass
  14. import cv2
  15. import numpy as np
  16. from config import PTZ_CAMERA, PTZ_CONFIG
  17. from dahua_sdk import DahuaSDK, PTZCommand
  18. from video_lock import safe_read, safe_is_opened
  19. @dataclass
  20. class PTZPosition:
  21. """PTZ位置信息"""
  22. pan: float # 水平角度 (0-360度)
  23. tilt: float # 垂直角度 (-90到90度)
  24. zoom: float # 变倍 (1-最大倍数)
  25. class PTZCamera:
  26. """球机控制类"""
  27. def __init__(self, sdk: DahuaSDK, camera_config: Dict = None):
  28. """
  29. 初始化球机
  30. Args:
  31. sdk: 大华SDK实例
  32. camera_config: 摄像头配置
  33. """
  34. self.sdk = sdk
  35. self.config = camera_config or PTZ_CAMERA
  36. self.ptz_config = PTZ_CONFIG
  37. self.login_handle = None
  38. self.connected = False
  39. # 当前位置
  40. self.current_position = PTZPosition(pan=0, tilt=0, zoom=1)
  41. self.position_lock = threading.Lock()
  42. # 视频流 (用于校准时抓拍球机画面)
  43. self.rtsp_cap = None
  44. self._rtsp_lock = threading.Lock()
  45. self.current_frame = None
  46. self.frame_lock = threading.Lock()
  47. self.stream_thread = None
  48. self.running_stream = False
  49. self._camera_id = 'ptz' # 用于per-camera锁
  50. def connect(self) -> bool:
  51. """
  52. 连接球机
  53. Returns:
  54. 是否成功
  55. """
  56. print(f"[PTZCamera] 正在连接球机: IP={self.config['ip']}:{self.config['port']}, 通道={self.config['channel']}")
  57. login_handle, error = self.sdk.login(
  58. self.config['ip'],
  59. self.config['port'],
  60. self.config['username'],
  61. self.config['password']
  62. )
  63. if login_handle is None:
  64. print(f"[PTZCamera] 连接球机失败: IP={self.config['ip']}, 错误码={error}")
  65. print(f"[PTZCamera] 请检查: 1)IP地址是否正确 2)网络是否连通 3)用户名密码是否正确")
  66. return False
  67. self.login_handle = login_handle
  68. self.connected = True
  69. print(f"[PTZCamera] 成功连接球机: {self.config['ip']}, handle={login_handle}")
  70. print(f"[PTZCamera] 配置: 通道={self.config['channel']}, 默认变倍={self.ptz_config['default_zoom']}")
  71. return True
  72. def disconnect(self):
  73. """断开连接"""
  74. self.stop_stream()
  75. if self.login_handle:
  76. self.sdk.logout(self.login_handle)
  77. self.login_handle = None
  78. self.connected = False
  79. def start_stream_rtsp(self, rtsp_url: str = None) -> bool:
  80. """启动RTSP视频流 (用于校准时获取球机画面)"""
  81. if rtsp_url is None:
  82. rtsp_url = self.config.get('rtsp_url') or \
  83. f"rtsp://{self.config['username']}:{self.config['password']}@{self.config['ip']}:{self.config.get('rtsp_port', 554)}/cam/realmonitor?channel=1&subtype=1"
  84. try:
  85. # 先尝试FFmpeg后端
  86. new_cap = cv2.VideoCapture(rtsp_url, cv2.CAP_FFMPEG)
  87. if not new_cap.isOpened():
  88. # FFmpeg失败,尝试GStreamer后端(ARM64上更稳定)
  89. print(f"[PTZCamera] FFmpeg后端无法打开RTSP流,尝试GStreamer后端...")
  90. try:
  91. gst_cap = cv2.VideoCapture(rtsp_url, cv2.CAP_GSTREAMER)
  92. if gst_cap.isOpened():
  93. new_cap = gst_cap
  94. print(f"[PTZCamera] 使用GStreamer后端打开RTSP流成功")
  95. else:
  96. print(f"[PTZCamera] 无法打开RTSP流: {rtsp_url}")
  97. return False
  98. except Exception as ge:
  99. print(f"[PTZCamera] GStreamer后端也不可用: {ge}")
  100. return False
  101. new_cap.set(cv2.CAP_PROP_BUFFERSIZE, 1)
  102. with self._rtsp_lock:
  103. self.rtsp_cap = new_cap
  104. self.running_stream = True
  105. self.stream_thread = threading.Thread(target=self._stream_worker, daemon=True)
  106. self.stream_thread.start()
  107. print(f"[PTZCamera] RTSP视频流已启动")
  108. return True
  109. except Exception as e:
  110. print(f"[PTZCamera] RTSP流启动失败: {e}")
  111. return False
  112. def _stream_worker(self):
  113. """视频流工作线程"""
  114. import signal
  115. if hasattr(signal, 'pthread_sigmask'):
  116. try:
  117. signal.pthread_sigmask(signal.SIG_BLOCK, {signal.SIGINT})
  118. except (AttributeError, OSError):
  119. pass
  120. max_consecutive_errors = 50
  121. error_count = 0
  122. while self.running_stream:
  123. try:
  124. with self._rtsp_lock:
  125. cap = self.rtsp_cap
  126. if cap is None or not safe_is_opened(cap, self._camera_id):
  127. time.sleep(0.1)
  128. continue
  129. ret, frame = safe_read(cap, self._camera_id)
  130. if not ret or frame is None:
  131. error_count += 1
  132. if error_count > max_consecutive_errors:
  133. print("[PTZCamera] RTSP流连续读取失败,尝试重连...")
  134. self._reconnect_rtsp()
  135. error_count = 0
  136. time.sleep(0.01)
  137. continue
  138. error_count = 0
  139. with self.frame_lock:
  140. self.current_frame = frame.copy()
  141. time.sleep(0.001)
  142. except Exception as e:
  143. err_str = str(e)
  144. if 'async_lock' in err_str or 'Assertion' in err_str:
  145. print(f"[PTZCamera] FFmpeg内部错误,3秒后重建连接: {e}")
  146. time.sleep(3)
  147. self._reconnect_rtsp()
  148. else:
  149. print(f"[PTZCamera] 视频流错误: {e}")
  150. time.sleep(0.5)
  151. def _reconnect_rtsp(self):
  152. rtsp_url = self.config.get('rtsp_url') or \
  153. f"rtsp://{self.config['username']}:{self.config['password']}@{self.config['ip']}:{self.config.get('rtsp_port', 554)}/cam/realmonitor?channel=1&subtype=1"
  154. with self._rtsp_lock:
  155. if self.rtsp_cap is not None:
  156. try:
  157. self.rtsp_cap.release()
  158. except Exception:
  159. pass
  160. self.rtsp_cap = None
  161. time.sleep(1)
  162. try:
  163. new_cap = cv2.VideoCapture(rtsp_url, cv2.CAP_FFMPEG)
  164. if safe_is_opened(new_cap, self._camera_id):
  165. new_cap.set(cv2.CAP_PROP_BUFFERSIZE, 1)
  166. with self._rtsp_lock:
  167. self.rtsp_cap = new_cap
  168. print("[PTZCamera] RTSP流重连成功")
  169. else:
  170. print("[PTZCamera] RTSP流重连失败")
  171. try:
  172. new_cap.release()
  173. except Exception:
  174. pass
  175. except Exception as e:
  176. print(f"[PTZCamera] RTSP流重连异常: {e}")
  177. def get_frame(self) -> Optional[np.ndarray]:
  178. """获取球机当前帧"""
  179. with self.frame_lock:
  180. return self.current_frame.copy() if self.current_frame is not None else None
  181. def stop_stream(self):
  182. """停止视频流"""
  183. self.running_stream = False
  184. if self.stream_thread:
  185. self.stream_thread.join(timeout=2)
  186. self.stream_thread = None
  187. with self._rtsp_lock:
  188. if self.rtsp_cap:
  189. self.rtsp_cap.release()
  190. self.rtsp_cap = None
  191. def ptz_control(self, command: int, param1: int = 0, param2: int = 0,
  192. param3: int = 0, stop: bool = False) -> bool:
  193. """
  194. PTZ控制
  195. Args:
  196. command: 控制命令
  197. param1-3: 参数
  198. stop: 是否停止
  199. Returns:
  200. 是否成功
  201. """
  202. if not self.connected:
  203. print(f"[PTZCamera] PTZ控制失败: 未连接球机")
  204. return False
  205. if self.login_handle is None or self.login_handle <= 0:
  206. print(f"[PTZCamera] PTZ控制失败: 登录句柄无效 (handle={self.login_handle})")
  207. return False
  208. return self.sdk.ptz_control(
  209. self.login_handle,
  210. self.config['channel'],
  211. command, param1, param2, param3, stop
  212. )
  213. def move_up(self, speed: int = 4, stop: bool = False) -> bool:
  214. """向上移动"""
  215. return self.ptz_control(PTZCommand.UP, 0, speed, 0, stop)
  216. def move_down(self, speed: int = 4, stop: bool = False) -> bool:
  217. """向下移动"""
  218. return self.ptz_control(PTZCommand.DOWN, 0, speed, 0, stop)
  219. def move_left(self, speed: int = 4, stop: bool = False) -> bool:
  220. """向左移动"""
  221. return self.ptz_control(PTZCommand.LEFT, 0, speed, 0, stop)
  222. def move_right(self, speed: int = 4, stop: bool = False) -> bool:
  223. """向右移动"""
  224. return self.ptz_control(PTZCommand.RIGHT, 0, speed, 0, stop)
  225. def zoom_in(self, speed: int = 4, stop: bool = False) -> bool:
  226. """放大"""
  227. return self.ptz_control(PTZCommand.ZOOM_ADD, 0, speed, 0, stop)
  228. def zoom_out(self, speed: int = 4, stop: bool = False) -> bool:
  229. """缩小"""
  230. return self.ptz_control(PTZCommand.ZOOM_DEC, 0, speed, 0, stop)
  231. def stop_move(self) -> bool:
  232. """停止移动"""
  233. # 发送停止命令
  234. self.move_up(0, True)
  235. self.move_left(0, True)
  236. self.zoom_in(0, True)
  237. return True
  238. def goto_exact_position(self, pan: float, tilt: float, zoom: int) -> bool:
  239. """
  240. 三维精确定位
  241. Args:
  242. pan: 水平角度 (0-360度)
  243. tilt: 垂直角度 (-90到90度)
  244. zoom: 变倍 (1-128)
  245. Returns:
  246. 是否成功
  247. """
  248. param1 = int(pan * 10)
  249. param2 = int(tilt * 10)
  250. param3 = int(min(zoom, 128))
  251. print(f"[PTZCamera] goto_exact_position: pan={pan:.1f}° tilt={tilt:.1f}° zoom={zoom} → p1={param1} p2={param2} p3={param3}")
  252. result = self.ptz_control(PTZCommand.EXACTGOTO, param1, param2, param3)
  253. if result:
  254. with self.position_lock:
  255. self.current_position = PTZPosition(pan=pan, tilt=tilt, zoom=zoom)
  256. else:
  257. print(f"[PTZCamera] goto_exact_position FAILED!")
  258. return result
  259. def goto_preset(self, preset_id: int) -> bool:
  260. """
  261. 转到预置点
  262. Args:
  263. preset_id: 预置点ID
  264. Returns:
  265. 是否成功
  266. """
  267. return self.ptz_control(PTZCommand.POINT_GO, 0, preset_id, 0)
  268. def set_preset(self, preset_id: int) -> bool:
  269. """
  270. 设置预置点
  271. Args:
  272. preset_id: 预置点ID
  273. Returns:
  274. 是否成功
  275. """
  276. return self.ptz_control(PTZCommand.POINT_SET, 0, preset_id, 0)
  277. def clear_preset(self, preset_id: int) -> bool:
  278. """
  279. 清除预置点
  280. Args:
  281. preset_id: 预置点ID
  282. Returns:
  283. 是否成功
  284. """
  285. return self.ptz_control(PTZCommand.POINT_CLEAR, 0, preset_id, 0)
  286. def calculate_ptz_position(self, x_ratio: float, y_ratio: float,
  287. zoom: int = None) -> Tuple[float, float, int]:
  288. """
  289. 根据全景画面中的位置计算PTZ角度
  290. Args:
  291. x_ratio: X方向比例 (0-1)
  292. y_ratio: Y方向比例 (0-1)
  293. zoom: 变倍 (默认使用配置值)
  294. Returns:
  295. (pan, tilt, zoom) PTZ位置
  296. """
  297. if zoom is None:
  298. zoom = self.ptz_config['default_zoom']
  299. # 应用坐标偏移校准
  300. offset_x, offset_y = self.ptz_config['coordinate_offset']
  301. x_ratio = max(0, min(1, x_ratio + offset_x))
  302. y_ratio = max(0, min(1, y_ratio + offset_y))
  303. # 从配置获取视野参数
  304. pan_range = self.ptz_config.get('pan_range', (0, 180))
  305. tilt_range = self.ptz_config.get('tilt_range', (-45, 45))
  306. pan_center = self.ptz_config.get('pan_center', 90)
  307. tilt_center = self.ptz_config.get('tilt_center', 0)
  308. # 将画面比例转换为角度
  309. # x_ratio=0 对应 pan_range[0], x_ratio=1 对应 pan_range[1]
  310. pan = pan_range[0] + (pan_range[1] - pan_range[0]) * x_ratio
  311. # y_ratio=0.5 对应 tilt_center, y_ratio=0 对应 tilt_range[0], y_ratio=1 对应 tilt_range[1]
  312. tilt = tilt_range[0] + (tilt_range[1] - tilt_range[0]) * y_ratio
  313. # 应用方向修正
  314. # 1. 检查安装类型,吸顶安装需要反转tilt
  315. mount_type = self.ptz_config.get('mount_type', 'wall')
  316. tilt_flip = self.ptz_config.get('tilt_flip', False)
  317. # 吸顶安装时自动反转tilt方向
  318. if mount_type == 'ceiling' or tilt_flip:
  319. # 反转tilt:原来的正角度变负,负角度变正
  320. tilt = -tilt
  321. print(f"[PTZCamera] 吸顶安装,tilt方向修正: {-tilt} -> {tilt}")
  322. # 2. 应用pan方向修正
  323. pan_flip = self.ptz_config.get('pan_flip', False)
  324. if pan_flip:
  325. # 反转pan方向(180度偏移)
  326. pan = (pan + 180) % 360
  327. print(f"[PTZCamera] pan方向翻转: {(pan - 180) % 360} -> {pan}")
  328. return (pan, tilt, zoom)
  329. def move_to_target(self, x_ratio: float, y_ratio: float,
  330. zoom: int = None) -> bool:
  331. """
  332. 移动到目标位置
  333. Args:
  334. x_ratio: X方向比例 (0-1)
  335. y_ratio: Y方向比例 (0-1)
  336. zoom: 变倍
  337. Returns:
  338. 是否成功
  339. """
  340. pan, tilt, zoom = self.calculate_ptz_position(x_ratio, y_ratio, zoom)
  341. return self.goto_exact_position(pan, tilt, zoom)
  342. def track_target(self, x_ratio: float, y_ratio: float,
  343. zoom: int = None) -> bool:
  344. """
  345. 跟踪目标 - 与move_to_target相同,但可以添加跟踪特定逻辑
  346. Args:
  347. x_ratio: X方向比例
  348. y_ratio: Y方向比例
  349. zoom: 变倍
  350. Returns:
  351. 是否成功
  352. """
  353. return self.move_to_target(x_ratio, y_ratio, zoom)
  354. def get_current_position(self) -> PTZPosition:
  355. """获取当前位置"""
  356. with self.position_lock:
  357. return PTZPosition(
  358. pan=self.current_position.pan,
  359. tilt=self.current_position.tilt,
  360. zoom=self.current_position.zoom
  361. )
  362. def goto_and_confirm(self, pan: float, tilt: float, zoom: int,
  363. confirm_timeout: float = 1.0,
  364. get_frame_func=None) -> dict:
  365. """
  366. PTZ精确定位并确认到位
  367. Args:
  368. pan, tilt, zoom: 目标位置
  369. confirm_timeout: 确认超时秒数
  370. get_frame_func: 获取球机帧的函数,用于验证
  371. Returns:
  372. dict: {'success': bool, 'pan': float, 'tilt': float, 'zoom': int,
  373. 'frame_available': bool, 'elapsed_ms': float}
  374. """
  375. import time as _time
  376. start = _time.time()
  377. success = self.goto_exact_position(pan, tilt, zoom)
  378. result = {
  379. 'success': success,
  380. 'pan': pan,
  381. 'tilt': tilt,
  382. 'zoom': zoom,
  383. 'frame_available': False,
  384. 'elapsed_ms': (_time.time() - start) * 1000
  385. }
  386. if not success:
  387. return result
  388. # 等待球机物理移动到位
  389. time.sleep(0.2)
  390. # 如果有帧获取函数,验证球机画面
  391. if get_frame_func is not None:
  392. deadline = _time.time() + confirm_timeout
  393. while _time.time() < deadline:
  394. frame = get_frame_func()
  395. if frame is not None:
  396. result['frame_available'] = True
  397. break
  398. time.sleep(0.05)
  399. result['elapsed_ms'] = (_time.time() - start) * 1000
  400. return result
  401. def is_position_close(self, target_pan: float, target_tilt: float,
  402. threshold: float = 1.0) -> bool:
  403. """
  404. 检查当前位置是否接近目标位置
  405. Args:
  406. target_pan: 目标水平角度
  407. target_tilt: 目标垂直角度
  408. threshold: 角度容差(度)
  409. """
  410. current = self.get_current_position()
  411. pan_diff = abs(current.pan - target_pan)
  412. tilt_diff = abs(current.tilt - target_tilt)
  413. return pan_diff <= threshold and tilt_diff <= threshold
  414. class PTZController:
  415. """
  416. PTZ高级控制器
  417. 提供平滑移动、跟踪等功能
  418. """
  419. def __init__(self, ptz_camera: PTZCamera):
  420. """
  421. 初始化控制器
  422. Args:
  423. ptz_camera: PTZ摄像头实例
  424. """
  425. self.ptz = ptz_camera
  426. self.tracking = False
  427. self.tracking_thread = None
  428. self.target_position = None
  429. def smooth_move_to(self, pan: float, tilt: float, zoom: int,
  430. steps: int = 10, delay: float = 0.1) -> bool:
  431. """
  432. 平滑移动到目标位置
  433. Args:
  434. pan: 目标水平角度
  435. tilt: 目标垂直角度
  436. zoom: 目标变倍
  437. steps: 移动步数
  438. delay: 步间延迟
  439. Returns:
  440. 是否成功
  441. """
  442. current = self.ptz.get_current_position()
  443. # 计算步长
  444. pan_step = (pan - current.pan) / steps
  445. tilt_step = (tilt - current.tilt) / steps
  446. zoom_step = (zoom - current.zoom) / steps
  447. for i in range(1, steps + 1):
  448. current_pan = current.pan + pan_step * i
  449. current_tilt = current.tilt + tilt_step * i
  450. current_zoom = int(current.zoom + zoom_step * i)
  451. self.ptz.goto_exact_position(current_pan, current_tilt, current_zoom)
  452. time.sleep(delay)
  453. return True
  454. def start_tracking(self, get_target_func, update_interval: float = 0.1):
  455. """
  456. 开始跟踪
  457. Args:
  458. get_target_func: 获取目标位置的函数 (返回 x_ratio, y_ratio 或 None)
  459. update_interval: 更新间隔
  460. """
  461. self.tracking = True
  462. def tracking_worker():
  463. while self.tracking:
  464. try:
  465. target = get_target_func()
  466. if target:
  467. x_ratio, y_ratio = target
  468. self.ptz.track_target(x_ratio, y_ratio)
  469. time.sleep(update_interval)
  470. except Exception as e:
  471. print(f"跟踪错误: {e}")
  472. time.sleep(0.1)
  473. self.tracking_thread = threading.Thread(target=tracking_worker, daemon=True)
  474. self.tracking_thread.start()
  475. def stop_tracking(self):
  476. """停止跟踪"""
  477. self.tracking = False
  478. if self.tracking_thread:
  479. self.tracking_thread.join(timeout=1)
  480. self.tracking_thread = None
  481. def zoom_to_target_size(self, target_size: Tuple[int, int],
  482. frame_size: Tuple[int, int],
  483. min_zoom: int = 2, max_zoom: int = 20) -> int:
  484. """
  485. 根据目标大小计算合适的变倍
  486. Args:
  487. target_size: 目标尺寸 (width, height)
  488. frame_size: 画面尺寸 (width, height)
  489. min_zoom: 最小变倍
  490. max_zoom: 最大变倍
  491. Returns:
  492. 计算的变倍值
  493. """
  494. target_area = target_size[0] * target_size[1]
  495. frame_area = frame_size[0] * frame_size[1]
  496. # 目标占画面比例
  497. ratio = target_area / frame_area
  498. # 根据比例计算变倍 (目标占画面30%时变倍为1)
  499. if ratio > 0:
  500. ideal_zoom = math.sqrt(0.3 / ratio)
  501. zoom = int(max(min_zoom, min(max_zoom, ideal_zoom)))
  502. else:
  503. zoom = min_zoom
  504. return zoom