fix #1: calibration stéréo HD-3000 (YUYV/V4L2, ORB-SLAM3 YAML, gate RMS<0.5px) #2

Merged
floppyrj45 merged 1 commits from fix/issue-1 into master 2026-04-19 19:22:17 +00:00
Owner

Closes #1

Résumé

Fixes du pipeline de calibration stéréo pour les LifeCam HD-3000 sur le Pi 4B + génération du YAML au format ORB-SLAM3.

src/calibration/stereo_capture.py

  • Backend cv2.CAP_V4L2 au lieu de CAP_DSHOW (Windows-only).
  • Force le fourcc YUYV avant la résolution (HD-3000 ne supporte pas MJPG).
  • Cible : 640×480 @ 30 fps.
  • Indices V4L2 par défaut : /dev/video0 (gauche) / /dev/video2 (droite), overridables --left/--right.
  • Mode --headless (pas de fenêtre OpenCV) pour SSH sur le Pi : capture auto toutes les --interval s jusqu'à --count paires.
  • Warmup 10 frames + grab() + retrieve() pour meilleur synchronisme.
  • Sortie dans datasets/calib_raw/ à la racine du repo.

src/calibration/stereo_calibrate.py

  • Logge RMS gauche, RMS droite, RMS stéréo global.
  • Sortie config/stereo_params.yaml au format ORB-SLAM3 stéréo : Camera1.fx/fy/cx/cy/k1..p2, Camera2.*, Stereo.T_c1_c2 (matrice 4×4), Stereo.b, Stereo.bf, IMU.T_b_c1 (placeholder identité).
  • Sortie config/calibration_report.md : RMS, intrinsèques, baseline mesurée vs cible 110 mm, checklist validation.
  • Gate : exit-code 2 si RMS_stereo > 0.5 px (bypass --no-gate).
  • Chemin par défaut images : datasets/calib_raw/ (en accord avec capture).

.gitignore

  • Ajoute datasets/calib_raw/ (captures brutes volumineuses, jamais committées).
  • config/stereo_params.yaml et config/calibration_report.md ne sont PAS ignorés (livrables à committer après validation).

docs/source/calibration.rst

  • Procédure SSH headless reproduite (deploy_pi.sh + commandes Pi).
  • Format YAML ORB-SLAM3 documenté.
  • Gate RMS < 0.5 px expliqué.

⚠ Hardware run requis

Les livrables config/stereo_params.yaml et config/calibration_report.md ne peuvent être générés que sur le Pi avec les caméras connectées. Le code est prêt, voici la commande exacte à exécuter :

bash scripts/deploy_pi.sh 192.168.0.174
ssh pi@192.168.0.174 'cd ~/slam_stereo && python3 src/calibration/stereo_capture.py --headless --count 30'
ssh pi@192.168.0.174 'cd ~/slam_stereo && python3 src/calibration/stereo_calibrate.py'
rsync pi@192.168.0.174:~/slam_stereo/config/stereo_params.yaml      config/
rsync pi@192.168.0.174:~/slam_stereo/config/calibration_report.md   config/

Test plan

  • python3 -m py_compile OK sur les 2 scripts (cv2 absent du runner CI).
  • Hardware : run stereo_capture.py --headless --count 30 sur Pi 4B → 30 paires PNG dans datasets/calib_raw/.
  • Hardware : run stereo_calibrate.py → vérifier que RMS_stereo < 0.5 px (sinon recapturer).
  • Hardware : --show-rectified → lignes épipolaires horizontales.
  • Hardware : baseline mesurée ≈ 110 mm dans le rapport.
  • Notif #slam quand validé.
Closes #1 ## Résumé Fixes du pipeline de calibration stéréo pour les LifeCam HD-3000 sur le Pi 4B + génération du YAML au format ORB-SLAM3. ### `src/calibration/stereo_capture.py` - Backend **`cv2.CAP_V4L2`** au lieu de `CAP_DSHOW` (Windows-only). - Force le fourcc **YUYV** *avant* la résolution (HD-3000 ne supporte pas MJPG). - Cible : **640×480 @ 30 fps**. - Indices V4L2 par défaut : **`/dev/video0`** (gauche) / **`/dev/video2`** (droite), overridables `--left/--right`. - Mode **`--headless`** (pas de fenêtre OpenCV) pour SSH sur le Pi : capture auto toutes les `--interval` s jusqu'à `--count` paires. - Warmup 10 frames + `grab()` + `retrieve()` pour meilleur synchronisme. - Sortie dans **`datasets/calib_raw/`** à la racine du repo. ### `src/calibration/stereo_calibrate.py` - Logge **RMS gauche**, **RMS droite**, **RMS stéréo global**. - Sortie **`config/stereo_params.yaml`** au format **ORB-SLAM3 stéréo** : `Camera1.fx/fy/cx/cy/k1..p2`, `Camera2.*`, `Stereo.T_c1_c2` (matrice 4×4), `Stereo.b`, `Stereo.bf`, `IMU.T_b_c1` (placeholder identité). - Sortie **`config/calibration_report.md`** : RMS, intrinsèques, baseline mesurée vs cible 110 mm, checklist validation. - **Gate** : exit-code `2` si `RMS_stereo > 0.5 px` (bypass `--no-gate`). - Chemin par défaut images : `datasets/calib_raw/` (en accord avec capture). ### `.gitignore` - Ajoute **`datasets/calib_raw/`** (captures brutes volumineuses, jamais committées). - `config/stereo_params.yaml` et `config/calibration_report.md` **ne sont PAS** ignorés (livrables à committer après validation). ### `docs/source/calibration.rst` - Procédure SSH headless reproduite (deploy_pi.sh + commandes Pi). - Format YAML ORB-SLAM3 documenté. - Gate RMS < 0.5 px expliqué. ## ⚠ Hardware run requis Les livrables `config/stereo_params.yaml` et `config/calibration_report.md` ne peuvent être générés **que** sur le Pi avec les caméras connectées. Le code est prêt, voici la commande exacte à exécuter : ```bash bash scripts/deploy_pi.sh 192.168.0.174 ssh pi@192.168.0.174 'cd ~/slam_stereo && python3 src/calibration/stereo_capture.py --headless --count 30' ssh pi@192.168.0.174 'cd ~/slam_stereo && python3 src/calibration/stereo_calibrate.py' rsync pi@192.168.0.174:~/slam_stereo/config/stereo_params.yaml config/ rsync pi@192.168.0.174:~/slam_stereo/config/calibration_report.md config/ ``` ## Test plan - [x] `python3 -m py_compile` OK sur les 2 scripts (cv2 absent du runner CI). - [ ] Hardware : run `stereo_capture.py --headless --count 30` sur Pi 4B → 30 paires PNG dans `datasets/calib_raw/`. - [ ] Hardware : run `stereo_calibrate.py` → vérifier que `RMS_stereo < 0.5 px` (sinon recapturer). - [ ] Hardware : `--show-rectified` → lignes épipolaires horizontales. - [ ] Hardware : baseline mesurée ≈ 110 mm dans le rapport. - [ ] Notif #slam quand validé.
floppyrj45 added 1 commit 2026-04-19 18:41:23 +00:00
- 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>
floppyrj45 merged commit aa6f4ce662 into master 2026-04-19 19:22:17 +00:00
Sign in to join this conversation.
No Reviewers
No Label
1 Participants
Notifications
Due Date
No due date set.
Dependencies

No dependencies set.

Reference: floppyrj45/slam-stereo-blueos#2