SITL — simulateur ArduPilot sur macOS¶
SITL (Software In The Loop) exécute le vrai firmware ArduPilot compilé pour macOS, alimenté par un modèle physique. Tu vois ton avion virtuel répondre exactement comme le vrai.
Prérequis :
setup-macos.mdterminé.
1. Premier lancement¶
Au premier appel, sim_vehicle.py :
1. Compile SITL pour macOS via waf (~1m30 sur M1 Pro à froid, <10s sur builds incrémentaux grâce à ccache).
2. Lance le binaire arduplane (Mach-O arm64 natif, ~4.6 MB) avec un modèle de vol par défaut.
3. Ouvre MAVProxy (terminal) et la carte (fenêtre).
Smoke test rapide sans MAVProxy ni carte :
sim_vehicle.py -v ArduPlane --no-mavproxypuis depuis un autre terminalpython3 -c "from pymavlink import mavutil; m=mavutil.mavlink_connection('tcp:127.0.0.1:5760'); print(m.wait_heartbeat(timeout=10))". Si tu vois un HEARTBEAT, la chaîne est OK.
Pour relancer ensuite (sans recompiler) :
(Tools/autotest/sim_vehicle.py doit être dans ton PATH — sinon ajouter export PATH="$HOME/Project/bascanada/ardupilot/Tools/autotest:$PATH" à ~/.zshrc.)
2. Modèle Swordfish 1200¶
Par défaut, SITL utilise un modèle générique fixed-wing. Pour s'approcher du AtomRC Swordfish 1200 (bimoteur pusher + V-tail), on charge nos params custom :
sim_vehicle.py -v ArduPlane --add-param-file=$HOME/Project/bascanada/my_fleet/fleet-params/swordfish-h743-baseline.parm
Ou, SITL déjà démarré, depuis MAVProxy :
Le baseline est dérivé du .param officiel AtomRC (Swordfish 1200 sur F405-NAVI, 2022-12-05) — voir ../../fleet-params/README.md pour la justification de chaque choix et la convention de versionnage.
Valeurs clés (différent de ce qu'on imaginerait pour un FW classique) :
| Paramètre | Valeur AtomRC | Note |
|---|---|---|
TRIM_ARSPD_CM |
1200 (= 12 m/s) | AtomRC vise vol économique, pas vitesse |
WP_LOITER_RAD |
60 | Cercles serrés pour observation |
TRIM_THROTTLE |
45 | À cette vitesse, ~30-45 min sur pack 4S 4000 mAh |
SERVO1/2_FUNCTION |
70 | 2 moteurs — twin pusher |
RUDD_DT_GAIN |
10 | Différentiel de poussée pour assister le yaw |
Voir ../../fleet-params/swordfish-h743-baseline.parm pour le fichier commenté complet et training/06-tuning.md pour le workflow d'AUTOTUNE après assemblage.
3. Connexion QGroundControl¶
Le binaire arduplane lui-même expose MAVLink sur TCP 127.0.0.1:5760. C'est MAVProxy (lancé par sim_vehicle.py) qui s'y connecte et redistribue sur UDP 14550 vers QGC. QGC s'y connecte automatiquement au lancement.
Si plusieurs instances SITL tournent, MAVProxy peut redistribuer :
Configurer QGC : Application Settings → Comm Links → Add → UDP, port 14551.
4. Pilotage avec un joystick¶
QGC sur macOS détecte tout périphérique USB HID joystick. Trois options classées par fidélité au matériel réel :
| Option | Avantages | Inconvénients |
|---|---|---|
| Radiomaster Boxer (mode USB HID via EdgeTX) | Mêmes sticks/switches que sur le terrain — entraînement transférable 1:1 | Nécessite d'avoir la radio en main |
| Manette Xbox / PS (USB ou Bluetooth) | Matériel courant ; suffisant pour apprendre les modes et la logique d'armement | Pas le même feeling stick — réflexes ne transfèrent pas tels quels |
| Souris/clavier (via QGC virtuel) | Aucun matériel | Inutilisable pour piloter un fixed-wing en MANUAL |
Boxer (cible Phase 0.5 finale)¶
- Brancher en USB-C au Mac.
- À l'invite EdgeTX, choisir USB Joystick (HID).
- macOS la voit dans About This Mac → System Report → USB.
Xbox / PS (substitut en attendant la Boxer)¶
- USB : plug-and-play sur macOS récent (Sonoma+).
- Bluetooth : Settings → Bluetooth → maintenir le bouton Pair de la manette.
- Mapping QGC standard : stick gauche = throttle/yaw (mode 2), stick droit = pitch/roll, boutons = changements de mode.
Côté QGC (commun)¶
- Application Settings → Joystick → activer.
- Calibrer les axes (suivre l'assistant : déplacer chaque stick aux extrêmes).
- Mapper les boutons aux modes de vol (MANUAL, FBWA, AUTO, RTL, ARM/DISARM).
Côté SITL¶
Démarrer SITL avec injection joystick autorisée :
Le -j autorise QGC à injecter les canaux RC virtuels via MAVLink (MANUAL_CONTROL / RC_CHANNELS_OVERRIDE).
Note importante sur la Xbox : utile pour apprendre les modes, la logique d'armement, et la lecture de la télémétrie, pas pour acquérir des réflexes stick. Pour le pilotage manuel proprement dit, attendre la Boxer.
5. Scénario multi-véhicules — avion + rover¶
Pour valider la logique de coordination Phase 4, lancer deux SITL en parallèle dans deux terminaux :
Terminal 1 (avion) :
Terminal 2 (rover) :
Le flag -I donne un identifiant d'instance différent → ports SITL distincts (TCP 5760 + I×10, soit 5760 pour Plane et 5770 pour Rover dans cet exemple).
Attention SYSID :
-Ichange le port mais pasSYSID_THISMAV— par défaut, les deux véhicules conserventsysid=1. Tant que tu utilises deux Comm Links UDP distincts dans QGC (14550 et 14560), QGC les distingue par lien et tout va bien. Si tu agrèges les deux flux dans une seule MAVProxy hub, change explicitementSYSID_THISMAV=2(ou plus) sur le rover viaparam setpour éviter la collision.
Dans QGC, ajouter deux Comm Links UDP (14550 et 14560). QGC affiche les deux véhicules dans le sélecteur en haut.
6. Visualisation 3D externe — FlightGear¶
Pour un rendu 3D avec terrain réel (utile pour s'entraîner visuellement, valider une mission de scouting, faire une démo), on branche FlightGear comme renderer 3D.
Lancement intégré :
Voir flightgear.md pour le guide détaillé (intégration, scenery, points d'intérêt Rive-Sud, troubleshooting, vues utiles en vol).
SITL reste l'autorité physique — FG est strictement un viewer qui consomme un FDM externe sur UDP 5503. La chaîne MAVLink → Cockpit/QGC tourne en parallèle, FG ne perturbe rien.
Gazebo n'est pas recommandé sur macOS pour cette stack. À considérer plus tard (Phase 4+) si on veut simuler une caméra Pi pour fleet-companion — là où FG ne suffit plus.
7. Cycle de dev typique¶
- Modifier un paramètre ou un script de mission.
- Relancer SITL (ou recharger les paramètres dans QGC).
- Armer, takeoff (commande MAVProxy :
arm throttlepuismode takeoff). - Observer la trajectoire dans QGC.
- Itérer.
Pour Phase 0.5, l'objectif est 100 cycles décollage / vol / atterrissage virtuels avant tout vol réel. Pas pour devenir un as du stick, mais pour avoir les réflexes de mode-switching et de RTL d'urgence.
8. Mission scriptée — test sans GUI¶
Pour valider la chaîne complète SITL + autopilot + commande MAVLink en CI ou en smoke test, sans toucher à QGC :
# scripted-takeoff.py
from pymavlink import mavutil
import time
m = mavutil.mavlink_connection("tcp:127.0.0.1:5760")
m.wait_heartbeat()
m.mav.set_mode_send(m.target_system,
mavutil.mavlink.MAV_MODE_FLAG_CUSTOM_MODE_ENABLED, 13) # 13 = TAKEOFF
m.mav.command_long_send(m.target_system, m.target_component,
mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM, 0, 1,0,0,0,0,0,0)
t0 = time.time()
while time.time() - t0 < 30:
msg = m.recv_match(type="GLOBAL_POSITION_INT", blocking=True, timeout=2)
if msg:
print(f"alt={msg.relative_alt/1000:.1f} m")
Lancer SITL en parallèle (sim_vehicle.py -v ArduPlane --no-mavproxy), puis ce script. Test validé 2026-05-10 : altitude max ~60 m après ~10 s.
Références¶
- ArduPilot SITL — https://ardupilot.org/dev/docs/sitl-simulator-software-in-the-loop.html
- sim_vehicle.py options —
sim_vehicle.py --help - MAVProxy commands — https://ardupilot.org/mavproxy/docs/uav_configuration/index.html