Carte Navigator — BMI088 IMU ============================= La carte Navigator de Blue Robotics embarque : - **IMU** : Bosch BMI088 (accéléromètre 6-axes + gyroscope 6-axes, séparés physiquement) - **Baromètre** : TE MS5837-30BA (profondimètre 300 bar) - **PWM** : NXP PCA9685 (16 canaux, contrôle thrusters via ArduSub) Spécifications BMI088 --------------------- .. list-table:: :header-rows: 1 * - Paramètre - Valeur * - Plage accéléromètre - ±3g / ±6g / ±12g / ±24g * - Bruit accéléromètre - 175 μg/√Hz * - Plage gyroscope - ±125 à ±2000 °/s * - Bruit gyroscope - 0.014 °/s/√Hz * - Interface - SPI / I2C * - Fréquence sortie - 100–400 Hz (configurable) Accès via BlueOS / MAVLink --------------------------- ArduSub lit le BMI088 via l'interface SPI interne de la Navigator. Les données IMU sont accessibles en MAVLink (message ``SCALED_IMU``). .. code-block:: python from pymavlink import mavutil mav = mavutil.mavlink_connection('udpin:192.168.0.174:14550') mav.wait_heartbeat() while True: msg = mav.recv_match(type='SCALED_IMU', blocking=True) if msg: ax = msg.xacc / 1000.0 # mg -> g ay = msg.yacc / 1000.0 az = msg.zacc / 1000.0 gx = msg.xgyro / 1000.0 # mrad/s -> rad/s print(f"Acc: {ax:.3f} {ay:.3f} {az:.3f} g") Fusion visuo-inertielle (VIO) ------------------------------ ORB-SLAM3 mode **Stereo-Inertial** requiert : 1. Extrinsèques IMU-caméra (matrice ``T_cam_imu``) — à calibrer via Kalibr 2. Biais accéléromètre et gyroscope (InitialAccBias, InitialGyroBias) 3. Fréquence IMU ≥ 200 Hz (configurer ArduSub ``IMU_FAST_RATE=1``) Fichier config ORB-SLAM3 : ``config/navigator_imu.yaml`` (à générer après calibration Kalibr). Références ---------- - `Blue Robotics Navigator Documentation `_ - BMI088 Datasheet — Bosch Sensortec BST-BMI088-DS001