Files
slam-stereo-blueos/docs/source/calibration.rst
Silver Surfer 3398ec7751 fix #1: calibration stéréo HD-3000 (YUYV/V4L2, ORB-SLAM3 YAML, gate RMS<0.5px)
- stereo_capture.py : backend V4L2 + fourcc YUYV 640×480@30 (HD-3000 ne supporte
  pas MJPG), indices /dev/video0 et /dev/video2, mode --headless pour SSH,
  warmup AE/AGC, grab+retrieve pour meilleur synchronisme, sortie
  datasets/calib_raw/ à la racine du repo.
- stereo_calibrate.py : log RMS per-cam + RMS stéréo global, écrit
  config/stereo_params.yaml au format ORB-SLAM3 (Camera1/2.fx, Stereo.T_c1_c2,
  Stereo.b/bf, IMU.T_b_c1 placeholder), génère config/calibration_report.md
  avec baseline mesurée vs cible 110 mm. Gate exit-code 2 si RMS > 0.5 px
  (bypass --no-gate).
- .gitignore : ajoute datasets/calib_raw/ (captures brutes volumineuses).
- docs/source/calibration.rst : procédure SSH headless reproduite, format YAML
  ORB-SLAM3 documenté, gate RMS<0.5 px expliqué.

Note : la calibration numérique (RMS, K/D/R/T, baseline mesurée) doit être
exécutée sur le Pi avec les caméras connectées — code prêt, hardware run à
faire manuellement.

Co-Authored-By: Claude Opus 4.7 (1M context) <noreply@anthropic.com>
2026-04-19 18:40:58 +00:00

139 lines
4.3 KiB
ReStructuredText
Raw Blame History

This file contains ambiguous Unicode characters
This file contains Unicode characters that might be confused with other characters. If you think that this is intentional, you can safely ignore this warning. Use the Escape button to reveal them.
Calibration Stéréo
==================
Matériel nécessaire
-------------------
- Damier imprimé **9×6 cases** (intérieur), case **25 mm**
- Support rigide (plastifié recommandé)
- Éclairage uniforme sans reflets
- 2× Microsoft LifeCam HD-3000 sur ``/dev/video0`` (gauche) et
``/dev/video2`` (droite), baseline cible **110 mm**
.. warning::
Imprimer sur fond blanc mat. Plastifier sans brillance pour éviter
les reflets. Ne pas utiliser d'écran LCD (déformation optique).
.. note::
Les HD-3000 ne supportent **pas** le format MJPG. La capture est forcée
en **YUYV 640×480 @ 30 fps** (cf. ``cap.set(CAP_PROP_FOURCC, "YUYV")``).
La résolution doit être appliquée *après* le fourcc, sinon V4L2 l'ignore.
Procédure (issue #1)
--------------------
Étape 0 — Déploiement sur le Pi
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. code-block:: bash
bash scripts/deploy_pi.sh 192.168.0.174
Étape 1 — Capture des paires (sur le Pi, en SSH)
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. code-block:: bash
ssh pi@192.168.0.174
cd ~/slam_stereo
# Mode interactif (avec écran X11 forwardé) :
python3 src/calibration/stereo_capture.py
# OU mode headless (recommandé en SSH, pas d'écran) :
python3 src/calibration/stereo_capture.py --headless --count 30 --interval 2.0
- Indices V4L2 par défaut : gauche = ``0``, droite = ``2``
(override : ``--left N --right M``)
- Sorties dans ``datasets/calib_raw/`` (gitignored)
- Objectif : **≥ 25 paires valides** (varier distance 0.31.5 m, inclinaison ±30°,
position dans le frame, couvrir les 4 coins + centre)
- Alim USB du Pi flaky : éviter les sessions longues, libérer les caméras
entre les runs (``cap.release()`` est appelé dans ``finally``).
Étape 2 — Calibration (sur le Pi ou rapatrié sur PC)
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
.. code-block:: bash
python3 src/calibration/stereo_calibrate.py
Sortie attendue :
.. code-block:: text
[INFO] Chargement 30 paires depuis datasets/calib_raw
[INFO] Gauche: 28/30 images valides
[INFO] Droite: 27/30 images valides
[INFO] 26 paires valides pour calibration stéréo
[INFO] RMS gauche = 0.31 px
[INFO] RMS droite = 0.34 px
[INFO] RMS stéréo global = 0.42 px
[OK] YAML ORB-SLAM3 → config/stereo_params.yaml
[OK] Rapport → config/calibration_report.md
[OK] RMS stéréo 0.4200 < 0.5 px ✓
**Gate** : si RMS stéréo > 0.5 px → exit-code 2 (``[STOP]``). Recapturer
la mire (mauvais positionnement, flou de bougé, cams sous-focales).
Le bypass ``--no-gate`` existe mais ne dispense pas de re-capturer.
Livrables (commit après validation)
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
- ``config/stereo_params.yaml`` — format ORB-SLAM3 stéréo
(``Camera1.fx``, ````, ``Stereo.T_c1_c2``, ``Stereo.bf``, ``IMU.T_b_c1``…)
- ``config/calibration_report.md`` — RMS per-cam + RMS stéréo + baseline mesurée
Format YAML ORB-SLAM3 généré
----------------------------
.. code-block:: yaml
%YAML:1.0
File.version: "1.0"
Camera.type: "PinHole"
Camera1.fx: 525.123 # cam gauche
Camera1.fy: 524.987
Camera1.cx: 319.876
Camera1.cy: 239.234
Camera1.k1: -0.05432 # distorsion Plumb-Bob (4 coefs)
Camera1.k2: 0.00821
Camera1.p1: 0.00012
Camera1.p2: -0.00045
Camera2.fx: 525.456 # cam droite
# …
Camera.width: 640
Camera.height: 480
Camera.fps: 30
Stereo.T_c1_c2: !!opencv-matrix # transfo cam_droite → cam_gauche
rows: 4
cols: 4
dt: f
data: [...]
Stereo.b: 0.110000 # baseline (m)
Stereo.bf: 57.7600 # baseline * fx
Stereo.ThDepth: 40.0
IMU.T_b_c1: !!opencv-matrix # placeholder identité
rows: 4
cols: 4
dt: f
data: [1,0,0,0, 0,1,0,0, 0,0,1,0, 0,0,0,1]
Validation
----------
1. Erreur RMS stéréo **< 0.5 px** (gate strict, issue #1)
2. Lignes épipolaires horizontales sur image rectifiée
(``python3 src/calibration/stereo_calibrate.py --show-rectified``)
3. Translation ``T ≈ [-0.110, 0, 0]`` m (baseline sur axe X)
4. Épipole à l'infini après rectification (caméras parallèles)
Références
----------
:cite:`bradski2008learning` — OpenCV stereoCalibrate, stereoRectify.
:cite:`ferrera2019underwater` — Prise en compte réfraction eau/verre.