ModalAI Forum
    • Categories
    • Recent
    • Tags
    • Popular
    • Users
    • Groups
    • Register
    • Login
    1. Home
    2. qt
    Q
    • Profile
    • Following 0
    • Followers 0
    • Topics 1
    • Posts 7
    • Best 0
    • Controversial 0
    • Groups 0

    qt

    @qt

    0
    Reputation
    3
    Profile views
    7
    Posts
    0
    Followers
    0
    Following
    Joined Last Online

    qt Unfollow Follow

    Latest posts made by qt

    • RE: Starling 2 MAX GPS Mount CAD Model

      Hello @Ryan-Min,
      As far as I know, there is no specific CAD model file for the GPS mast. You should use the complete CAD model of the Starling 2 Max drone, which is available for download in the developer download section. You will need to create an account.
      Here is a direct link to the most recent version of the model, the version V3 : D0012-4-V3-C28-M36-T7-K0-Starling2-Max-V3-20260317.step
      The latest changes to the model are intended to improve GNSS performance. You can consult the documentation page EMI Mitigation for GNSS Applications for more information on this topic and to see their recommendations.

      posted in 3D Models
      Q
      qt
    • RE: PX4 -> QGC connection through USB for VOXL2

      @Alex-Kushleyev
      That's not perfect but I created a shell script based on https://docs.modalai.com/qgc-via-adb/ for the drone configuraiton.
      For my PC configuration, I created an udev rule to force an interface name since usb0 is renamed in "enx******". My udev rule can only work with my drone (I think). To define IP address, I add a conf file in /etc/systemd/network/
      I have only tested on my linux and it works perfectly :

      #!/usr/bin/env bash
      set -euo pipefail
      
      # See ModalAI doc : https://docs.modalai.com/qgc-via-adb/
      
      UDEV_RULE_DRONE="/etc/udev/rules.d/80-usb-ncm.rules"
      UDEV_RULE_PC="/etc/udev/rules.d/99-voxl-usb-ncm.rules"
      SYSTEMD_CONF_PC="/etc/systemd/network/10-voxl0.network"
      
      USB_COMP_QUALCOM="/sbin/usb/compositions/901D"
      
      # Network configuration
      USB_IFACE="usb0"
      USB_NET="192.168.7.0/24"
      PC_IP="192.168.7.1"
      DRONE_IP="192.168.7.2"
      NM_CONN_NAME="voxl-usb-ncm"
      
      show_help() {
          echo "Usage: $0 [--pc] [--drone] [--uninstall]"
          echo
          echo "Enable USB NCM networking for ModalAI VOXL / Starling 2 Max"
          echo
          echo "Options:"
          echo "  --pc         Configure host PC only"
          echo "  --drone      Configure drone via adb only"
          echo "  --uninstall  Remove configuration"
          echo "  --help       Show this help"
          echo
          echo "Defaults: if neither --pc nor --drone is provided, both are processed."
      }
      
      do_pc_install() {
          echo "[INFO][PC] Installing udev rule for VOXL USB NCM"
      
          cat > "$UDEV_RULE_PC" <<EOF
      SUBSYSTEM=="net", ACTION=="add", ATTRS{idVendor}=="05c6", ATTRS{idProduct}=="901d", ATTRS{serial}=="890d035c", NAME="voxl0"
      EOF
      
          echo "[INFO][PC] Creating systemd-networkd config for voxl0"
      
          cat > "$SYSTEMD_CONF_PC" <<EOF
      [Match]
      Name=voxl0
      
      [Network]
      Address=${PC_IP}/24
      LinkLocalAddressing=no
      IPv6AcceptRA=no
      EOF
      
          echo "[INFO][PC] Reloading udev rules"
          udevadm control --reload-rules
          udevadm trigger
      
          echo "[INFO][PC] Restarting systemd-networkd"
          systemctl restart systemd-networkd
      
          echo "[INFO][PC] PC installation complete"
      }
      
      do_pc_uninstall() {
          echo "[INFO][PC] Removing PC configuration"
      
          if [ -f "$UDEV_RULE_PC" ]; then
            rm -f "$UDEV_RULE_PC"
            echo "[INFO][PC] Removed udev rule"
          fi
      
          if [ -f "$SYSTEMD_CONF_PC" ]; then
            rm -f "$SYSTEMD_CONF_PC"
            echo "[INFO][PC] Removed systemd-networkd config"
          fi
      
          echo "[INFO][PC] Reloading udev rules"
          udevadm control --reload-rules
          udevadm trigger
      
          echo "[INFO][PC] Restarting systemd-networkd"
          systemctl restart systemd-networkd
      
          echo "[INFO][PC] PC uninstallation complete"
      }
      
      do_drone_install() {
          echo "[INFO][DRONE] Enabling USB NCM networking on VOXL via adb"
      
          adb root
          adb remount
      
          echo "[INFO][DRONE] Updating USB composition in Qualcomm script \
      $USB_COMP_QUALCOM configure the usb gadget with \
      the addition of the function NCM"
          echo "[INFO][DRONE] In $USB_COMP_QUALCOM, \
      add the line 'ln -s functions/ncm.0 configs/c.1/f3 2>/dev/null | true' \
      just after the line 'ln -s functions/ffs.adb configs/c.1/f2'"
          
          adb shell "sed -i '/ln -s functions\\/ffs.adb configs\\/c.1\\/f2/a \
          \\        ln -s functions\\/ncm.0 configs\\/c.1\\/f3 2>\\/dev\\/null | true' \
          $USB_COMP_QUALCOM"
      
          echo "[INFO][DRONE] Creating udev rule $UDEV_RULE_DRONE for usb0 with IP ${DRONE_IP}"
          
          adb shell "cat << 'EOF' > $UDEV_RULE_DRONE
      ACTION==\"add\", SUBSYSTEM==\"net\", KERNEL==\"usb0\", \
      RUN+=\"/bin/sh -c 'sleep 2; /sbin/ifconfig usb0 ${DRONE_IP} netmask 255.255.255.0 up'\"
      EOF"
      
          echo "[INFO][DRONE] NCM enabled — reboot required"
      }
      
      do_drone_uninstall() {
          echo "[INFO][DRONE] Removing NCM configuration"
      
          adb root
          adb remount
      
          echo "[INFO][DRONE] Removing udev rule $UDEV_RULE_DRONE"
          adb shell "rm -f $UDEV_RULE_DRONE || true"
      
          echo "[INFO][DRONE] Reverting USB composition (901D)"
          adb shell "
          sed -i '/ln -s functions\\/ncm.0 configs\\/c.1\\/f3/d' \
          $USB_COMP_QUALCOM
          "
      
          echo "[INFO][DRONE] USB NCM configuration removed"
          echo "[INFO][DRONE] Reboot required to fully apply changes"
      }
      
      
      # Arg parsing
      TARGET_PC=false
      TARGET_DRONE=false
      DO_UNINSTALL=false
      
      for arg in "$@"; do
        case "$arg" in
          --help) show_help; exit 0 ;;
          --pc) TARGET_PC=true ;;
          --drone) TARGET_DRONE=true ;;
          --uninstall) DO_UNINSTALL=true ;;
          *)
            echo "[ERROR] Unknown argument: $arg";
            show_help;
            exit 1 ;;
        esac
      done
      
      # Default to both if none selected
      if ! $TARGET_PC && ! $TARGET_DRONE; then
        TARGET_PC=true
        TARGET_DRONE=true
      fi
      
      # Execute
      if $DO_UNINSTALL; then
        $TARGET_PC && do_pc_uninstall
        $TARGET_DRONE && do_drone_uninstall
      else
        $TARGET_PC && do_pc_install
        $TARGET_DRONE && do_drone_install
      fi
      
      echo "[INFO] All done."
      ``
      
      posted in Ask your questions right here!
      Q
      qt
    • RE: Time Of Flight (TOF) camera output FPS divided by 5 after upgrading from SDK 1.5.0 to SDK 1.6.3 (Starling2 Max C29)

      @Alex-Kushleyev, thank you for your answer.
      I confirm your assumption, when I set the decimator to 1, the fps is not divided.
      Here are the tests I did on SDK 1.5.0 and SDK 1.6.3 :

      • test with SDK 1.5.0 ;
      fps = 10 | standy_enabled = false or true | decimator = 5
      
      | Pipe Name |  bytes  | wide |  hgt |exp(ms)| gain | frame id |latency(ms)|  fps |  mbps  | format
      | tof_depth |   43200 |  180 |  240 |  2.90 |    0 |     1540 |     28.0  | 10.0 |    3.5 | RAW8
      
      timestamp(ms)|  w  |  h  | Zmax | center point (m) (conf)
           7170622 | 240 | 180 |  7.1 | -0.0   0.0   0.0    0
      
      fps = 60 | standy_enabled = false or true | decimator = 5
      
      | Pipe Name |  bytes  | wide |  hgt |exp(ms)| gain | frame id |latency(ms)|  fps |  mbps  | format
      | tof_depth |   43200 |  180 |  240 |  1.30 |    0 |     2155 |      9.3  | 59.9 |   20.7 | RAW8
      
      timestamp(ms)|  w  |  h  | Zmax | center point (m) (conf)
          10666991 | 240 | 180 |  3.1 |  0.0   0.0   0.0    0
      
      fps = 60 | standy_enabled = false or true | decimator = 5
      
      | Pipe Name |  bytes  | wide |  hgt |exp(ms)| gain | frame id |latency(ms)|  fps |  mbps  | format
      | tof_depth |   43200 |  180 |  240 |  1.18 |    0 |      869 |      9.4  | 59.9 |   20.7 | RAW8
      
      timestamp(ms)|  w  |  h  | Zmax | center point (m) (conf)
          10753813 | 240 | 180 |  3.1 |  0.0   0.0   0.0    0
      
      • test with SDK 1.6.3
      fps = 10 | standy_enabled = true or false | decimator = 1
      
      | Pipe Name |  bytes  | wide |  hgt |exp(ms)| gain | frame id |latency(ms)|  fps |  mbps  | format
      | tof_depth |   43200 |  180 |  240 |  3.02 |    0 |      260 |     29.7  | 10.0 |    3.5 | RAW8
      
      timestamp(ms)|  w  |  h  | Zmax | center point (m) (conf)
           2052194 | 240 | 180 |  7.1 | -0.0   0.0   0.0    0
      
      fps = 60 | standy_enabled = true or false | decimator = 1
      
      | Pipe Name |  bytes  | wide |  hgt |exp(ms)| gain | frame id |latency(ms)|  fps |  mbps  | format
      | tof_depth |   43200 |  180 |  240 |  1.18 |    0 |     7532 |      9.3  | 59.9 |   20.7 | RAW8
      
      timestamp(ms)|  w  |  h  | Zmax | center point (m) (conf)
           2190721 | 240 | 180 |  3.1 |  0.0   0.0   0.0    0
      
      fps = 60 | standy_enabled = true or false | decimator = 10
      
      | Pipe Name |  bytes  | wide |  hgt |exp(ms)| gain | frame id |latency(ms)|  fps |  mbps  | format
      | tof_depth |   43200 |  180 |  240 |  1.20 |    0 |       83 |     10.1  |  6.0 |    2.1 | RAW8
      
      timestamp(ms)|  w  |  h  | Zmax | center point (m) (conf)
           2469720 | 240 | 180 |  3.1 |  0.0   0.0   0.0    0
      

      As you can see, for SDK 1.5.0, fhe fps is NEVER divided, regardless of the value of standby_enabled.
      For SDK 1.6.3, fhe fps is ALWAYS divided, regardless of the value of standby_enabled.
      So, my problem is solved but I think you have a bug on the management of the paramater 'standby_enabled'.
      I fastly investigate the code of voxl-camera-server and I can't find where you are using 'standby_enabled'. Here is the search result in all the project :

      # Query: standby_en
      # ContextLines: 2
      
      6 results - 2 files
      
      include/common_defs.h:
        370      modal_exposure_msv_config_t  ae_msv_info;  ///< ModalAI AE data (MSV)
        371  
        372:     int     standby_enabled;       ///< Standby enabled for lidar
        373      int     decimator;             ///< Decimator to use for standby
        374  
      
      src/config_file.cpp:
        129          printf("    gain_min           : %d\n", cams[i].ae_msv_info.gain_min);
        130          printf("    gain_max           : %d\n", cams[i].ae_msv_info.gain_max);
        131:         printf("    standby_enabled:     %d\n", cams[i].standby_enabled);
        132          printf("    decimator:           %d\n", cams[i].decimator);
        133          printf("    independent_exposure:%d\n", cams[i].ind_exp);
      
        642          // standby settings for tof only
        643          if(is_tof_sensor(cam->type)) {
        644:             json_fetch_bool_with_default(item, "standby_enabled", (int*)&cam->standby_enabled, cam->standby_enabled);
        645              json_fetch_int_with_default  (item, "decimator", &cam->decimator,   cam->decimator);
        646          }
      
      

      Maybe you should add a condition in your function PerCameraMgr::ProcessTOFPreviewFrame():

      void PerCameraMgr::ProcessTOFPreviewFrame(mpa_ion_buf_t* buffer_info, camera_image_metadata_t meta)
      {
          tofFrameCounter++;
      
          if(grab_cpu_pitmode_active() && tofFrameCounter % (int)configInfo.decimator != 0){
              return;
          }
          auto noStridePlaneSize = static_cast<size_t>(pre_width*pre_height*1.5);
          auto realWidth = static_cast<uint32_t>(pre_width*1.5);
          uint8_t* noStridePlane;
          if (buffer_info->stride != realWidth) {
              noStridePlane = new uint8_t[noStridePlaneSize];
              removePlaneStride(buffer_info->stride, realWidth, buffer_info->height,
                                (uint8_t*) buffer_info->vaddress, noStridePlane);
          }
          else {
              noStridePlane = static_cast<uint8_t*>(buffer_info->vaddress);
          }
      
          uint16_t srcPixel16[pre_width * pre_height] = {0};
          // NOTE we don't actually puvblish tis particular metadata to the pipe
          // TOF data is published separately in a very different way to cameras
          meta.format     = IMAGE_FORMAT_RAW8;
          meta.size_bytes = pre_width * pre_height;
          meta.stride     = pre_width;
      
          Mipi12ToRaw16(meta.size_bytes, noStridePlane, srcPixel16);
          tof_interface->ProcessRAW16(srcPixel16, meta.timestamp_ns);
      
          if (buffer_info->stride != realWidth) {
              delete[] noStridePlane;
          }
          M_VERBOSE("Sent tof data to royale for processing\n");
      
          return;
      }
      

      Best regards
      Quentin

      posted in Support Request Format for Best Results
      Q
      qt
    • Time Of Flight (TOF) camera output FPS divided by 5 after upgrading from SDK 1.5.0 to SDK 1.6.3 (Starling2 Max C29)

      I would like to report a probable bug related to the TOF camera on my Starling 2 Max (configuration C29).
      I was previously running SDK 1.5.0, and the TOF camera was operating correctly at the frame rate specified in the file "/etc/modalai/voxl-camera-server.conf".
      I recently upgraded from SDK 1.5.0 to SDK 1.6.3 (I didn't try other SDK versions).
      Since then, the TOF camera runs at a frequency divided by 5. I tested this using the CLI inspection tool with the command "voxl-inspect-cam tof_depth" for different FPS values (same results in VOXL-Portal). I have not changed anything on the drone except the "fps" parameter in the configuration file "/etc/modalai/voxl-camera-server.conf".
      Here is my TOF camera configuration:

      "type": "pmd-tof-liow2",
      "name": "tof",
      "enabled":      true,
      "camera_id":    3,
      "fps":  10,
      "en_rotate":    true,
      "ae_mode":      "off",
      "gain_min":     0,
      "gain_max":     0,
      "exposure_max_us":      6000,
      "standby_enabled":      false,
      "decimator":    5
      

      Here are the results from "voxl-inspect-cam tof_depth" for different FPS values:

      fps = 5
      | Pipe Name |  bytes  | wide |  hgt |exp(ms)| gain | frame id |latency(ms)|  fps |  mbps  | format
      | tof_depth |   43200 |  180 |  240 | 48.00 |    0 |       26 |     28.1  |  1.0 |    0.3 | RAW8
      
      fps = 10
      | Pipe Name |  bytes  | wide |  hgt |exp(ms)| gain | frame id |latency(ms)|  fps |  mbps  | format
      | tof_depth |   43200 |  180 |  240 | 24.00 |    0 |       28 |     27.2  |  2.0 |    0.7 | RAW8
      
      fps = 15
      | Pipe Name |  bytes  | wide |  hgt |exp(ms)| gain | frame id |latency(ms)|  fps |  mbps  | format
      | tof_depth |   43200 |  180 |  240 | 16.00 |    0 |       16 |     28.6  |  3.0 |    1.0 | RAW8
      
      fps = 20
      | Pipe Name |  bytes  | wide |  hgt |exp(ms)| gain | frame id |latency(ms)|  fps |  mbps  | format
      | tof_depth |   43200 |  180 |  240 | 12.00 |    0 |       21 |     27.8  |  4.0 |    1.4 | RAW8
      
      fpx = 30
      | Pipe Name |  bytes  | wide |  hgt |exp(ms)| gain | frame id |latency(ms)|  fps |  mbps  | format
      | tof_depth |   43200 |  180 |  240 |  8.00 |    0 |       13 |     26.8  |  6.0 |    2.1 | RAW8
      
      fps = 60
      | Pipe Name |  bytes  | wide |  hgt |exp(ms)| gain | frame id |latency(ms)|  fps |  mbps  | format
      | tof_depth |   43200 |  180 |  240 |  4.00 |    0 |      288 |     10.0  | 12.0 |    4.1 | RAW8
      
      
      fps = (8, 12, 25, 35, 40, 45, 50, 65, 70, 75, 80, 85, 90, 100, 120, 135, 140, 150, 180)
      
      | Pipe Name |  bytes  | wide |  hgt |exp(ms)| gain | frame id |latency(ms)|  fps |  mbps  | format
      | tof_depth | Server Disconnected
      
      

      Looking at the code in "src/hal3_camera_mgr.cpp", it seems expected that other frame rates do not work anymore. Here is the relevant section:

      if (configInfo.type == SENSOR_TOF){
          if (configInfo.fps != 5 && configInfo.fps != 10 && configInfo.fps != 15 && configInfo.fps != 30 && configInfo.fps != 45){
              M_ERROR("Invalid TOF framerate: %d, must be either 5, 10, 15, 30, or 45\n", configInfo.fps);
              return -1;
          }
      }
      
      if (configInfo.type == SENSOR_TOF_LIOW2){
          if (configInfo.fps != 5 && configInfo.fps != 10 && configInfo.fps != 15 && configInfo.fps != 20 && configInfo.fps != 30 && configInfo.fps != 60){
              M_ERROR("Invalid TOF framerate: %d, must be either 5, 10, 15, 20, 30, or 60\n", configInfo.fps);
              return -1;
          }
      }
      

      Below are the full version details for SDK 1.6.3 (where the issue occurs):

      voxl2:~$ voxl-version
      ────────────────────────────────────────────────────────────────────────────────
      system-image: 1.8.06-M0054-14.1a-perf
      kernel:       #1 SMP PREEMPT Wed Oct 22 04:13:18 UTC 2025 4.19.125
      ────────────────────────────────────────────────────────────────────────────────
      hw platform:  M0054
      mach.var:     1.0.1
      SKU:          MRB-D0012-4-V2-C29-T9-M28-X0
      ────────────────────────────────────────────────────────────────────────────────
      voxl-suite:   1.6.3
      ────────────────────────────────────────────────────────────────────────────────
      Packages:
      Repo:  http://voxl-packages.modalai.com/ ./dists/qrb5165/sdk-1.6/binary-arm64/
      Last Updated: 2026-03-09 17:52:53
      List:
      libfc-sensor                   1.0.9
      libmodal-cv                    0.6.0
      libmodal-exposure              0.1.4
      libmodal-flow                  1.0.3
      libmodal-journal               0.2.7
      libmodal-json                  0.4.8
      libmodal-pipe                  2.14.11
      libqrb5165-io                  0.6.3
      libvoxl-cci-direct             0.3.3
      libvoxl-codec                  0.0.2
      libvoxl-cutils                 0.1.6
      modalai-slpi                   1.2.2
      mv-voxl                        0.1-r0
      qrb5165-bind                   0.1-r0
      qrb5165-dfs-server             0.2.0
      qrb5165-mini-tof-server        0.2.2
      qrb5165-rangefinder-server     0.1.6
      qrb5165-slpi-test-sig          01-r0
      qrb5165-tflite                 2.17.2
      voxl-bind-spektrum             0.1.1
      voxl-camera-calibration        0.6.1
      voxl-camera-server             2.2.19
      voxl-cassie-ros2               0.0.1
      voxl-ceres-solver              2:2.0.0-2
      voxl-configurator              1.1.5
      voxl-cpu-monitor               0.7.7
      voxl-docker-support            1.3.1
      voxl-elrs                      1.1.0
      voxl-esc                       1.5.7
      voxl-esptool                   0.2.0
      voxl-feature-tracker           0.5.2
      voxl-flow-server               0.3.6
      voxl-gphoto2-server            0.0.10
      voxl-imu-server                2.0.1
      voxl-io-server                 0.0.8
      voxl-jpeg-turbo                2.1.3-7
      voxl-lepton-server             1.3.3
      voxl-lepton-tracker            0.0.4
      voxl-libgeographic             1.0.0
      voxl-libgphoto2                0.0.4
      voxl-libuvc                    1.0.7
      voxl-logger                    0.6.1
      voxl-mavcam-manager            0.6.0
      voxl-mavlink                   0.1.6
      voxl-mavlink-server            1.4.14
      voxl-microdds-agent            3.0.0-0
      voxl-modem                     1.2.3
      voxl-mongoose                  7.19.0
      voxl-mpa-to-ros                0.3.9
      voxl-mpa-to-ros2               0.0.7
      voxl-mpa-tools                 1.5.6
      voxl-nano-tracker              0.1.7
      voxl-open-vins-server          0.6.0
      voxl-opencv                    4.5.5-3
      voxl-osd                       0.3.8
      voxl-portal                    0.8.7
      voxl-px4                       1.14.0-2.0.133
      voxl-px4-params                0.9.0
      voxl-qvio-server               1.2.3
      voxl-remote-id                 0.0.9
      voxl-reset-slpi                0.0.1
      voxl-ros2-foxy                 0.0.1
      voxl-state-estimator           0.0.6
      voxl-streamer                  0.8.0
      voxl-suite                     1.6.3
      voxl-tag-detector              0.1.0
      voxl-tflite-server             0.5.1
      voxl-utils                     2.0.2
      voxl-uvc-server                0.1.7
      voxl-vision-hub                1.9.21
      voxl-vtx                       2.0.2
      voxl-wavemux                   0.0.3
      voxl2-io                       0.0.3
      voxl2-security-hardening-utls  1.0-r0
      voxl2-system-image             1.8.06-r0
      voxl2-wlan                     1.0-r0
      ────────────────────────────────────────────────────────────────────────────────
      

      Below are the full version details for SDK 1.5.0 (where the TOF camera worked as expected):

      ────────────────────────────────────────────────────────────────────────────────
      system-image: 1.8.04-M0054-14.1a-perf
      kernel:       #1 SMP PREEMPT Mon Mar 24 22:31:58 UTC 2025 4.19.125
      ────────────────────────────────────────────────────────────────────────────────
      hw platform:  M0054
      mach.var:     1.0.1
      SKU:          MRB-D0012-4-V2-C29-T9-M28-X0
      ────────────────────────────────────────────────────────────────────────────────
      voxl-suite:   1.5.0
      ────────────────────────────────────────────────────────────────────────────────
      Packages:
      Repo:  http://voxl-packages.modalai.com/ ./dists/qrb5165/sdk-1.5/binary-arm64/
      Last Updated: 2026-02-05 12:12:50
      List:
      libfc-sensor                1.0.7
      libmodal-cv                 0.5.18
      libmodal-exposure           0.1.4
      libmodal-journal            0.2.6
      libmodal-json               0.4.7
      libmodal-pipe               2.13.2
      libqrb5165-io               0.5.0
      libvoxl-cci-direct          0.3.3
      libvoxl-cutils              0.1.5
      modalai-slpi                1.2.0
      mv-voxl                     0.1-r0
      qrb5165-bind                0.1-r0
      qrb5165-dfs-server          0.2.0
      qrb5165-imu-server          1.1.3
      qrb5165-mini-tof-server     0.2.2
      qrb5165-rangefinder-server  0.1.5
      qrb5165-slpi-test-sig       01-r0
      qrb5165-system-tweaks       0.3.6
      qrb5165-tflite              2.8.0-2
      voxl-bind-spektrum          0.1.1
      voxl-camera-calibration     0.6.0
      voxl-camera-server          2.2.4
      voxl-cassie-ros2            0.0.1
      voxl-ceres-solver           2:1.14.0-10
      voxl-configurator           1.0.2
      voxl-cpu-monitor            0.6.0
      voxl-cross-template         0.0.1
      voxl-docker-support         1.3.1
      voxl-elrs                   0.4.7
      voxl-esc                    1.5.4
      voxl-feature-tracker        0.5.2
      voxl-flow-server            0.3.6
      voxl-gphoto2-server         0.0.10
      voxl-joystick-server        0.0.6
      voxl-jpeg-turbo             2.1.3-7
      voxl-lepton-server          1.3.3
      voxl-lepton-tracker         0.0.4
      voxl-libgphoto2             0.0.4
      voxl-libuvc                 1.0.7
      voxl-logger                 0.5.3
      voxl-mavcam-manager         0.6.0
      voxl-mavlink                0.1.5
      voxl-mavlink-server         1.4.9
      voxl-microdds-agent         3.0.0-0
      voxl-modem                  1.1.8
      voxl-mongoose               7.7.0-2
      voxl-mpa-to-ros             0.3.9
      voxl-mpa-tools              1.4.0
      voxl-open-vins              0.4.19
      voxl-open-vins-server       0.3.12
      voxl-opencv                 4.5.5-3
      voxl-osd                    0.1.8
      voxl-portal                 0.7.11
      voxl-px4                    1.14.0-2.0.105
      voxl-px4-params             0.7.5
      voxl-qvio-server            1.2.0
      voxl-remote-id              0.0.9
      voxl-reset-slpi             0.0.1
      voxl-ros2-humble            0.0.3
      voxl-state-estimator        0.0.5
      voxl-streamer               0.7.5
      voxl-suite                  1.5.0
      voxl-tag-detector           0.0.5
      voxl-tflite-server          0.4.1
      voxl-utils                  1.4.8
      voxl-uvc-server             0.1.7
      voxl-vision-hub             1.8.23
      voxl-vtx                    1.4.7
      voxl-wavemux                0.0.1
      voxl2-io                    0.0.3
      voxl2-system-image          1.8.04-r0
      voxl2-wlan                  1.0-r0
      ────────────────────────────────────────────────────────────────────────────────
      

      Between versions 2.2.4 and 2.2.19 of the "voxl-camera-server" repository, I extracted the commits that modified the file "src/hal3_camera_mgr.cpp":

      a7f5ea0 | 2025-12-10 | Eric Katzfey | Fixed the rest of the compiler warnings for the qrb5165-2 build
      aa7b12d | 2025-12-05 | Alex Kushleyev | fix boson buffer pre-allocation size - the extra allocation should only be done in raw preview mode
      f461dc0 | 2025-11-11 | Tom Martinson | Merge branch 'ar0144-rotate-encoded' into dev
      3189b6b | 2025-11-10 | Alex Kushleyev | add option to invert boson output via a command
      a3ac28e | 2025-11-10 | Tom Martinson | add new ar0144 rotated sensor type
      bfce3c3 | 2025-11-10 | Alex Kushleyev | move some misp init code from camera mgr to misp
      25fe9b6 | 2025-11-10 | Alex Kushleyev | load body to imu extrinsics from file
      5289342 | 2025-11-07 | Alex Kushleyev | remove hist ae option; add manual and auto=lme_msv
      a279e3d | 2025-11-06 | Jacob Camarillo | Remove unused OSD code
      51cceec | 2025-11-06 | Alex Kushleyev | fix the neutral point of UV in monochrome YUVs from 127 to 128 for mono images sent to encoder
      d1a9da8 | 2025-10-30 | Alex Kushleyev | Add an option to rotate AR0144 encoded video
      86e1476 | 2025-10-29 | Alex Kushleyev | enable buffer recycling and camera customer register reinit for recovery
      2b9816f | 2025-10-29 | Alex Kushleyev | Add boson 14bit support
      cda94c2 | 2025-10-09 | zauberflote | Enable misp in stereo config
      eeda888 | 2025-09-25 | Alex Kushleyev | enable rotation of imx412 and imx664 via en_rotate config option. using cci direct to set the readout direction
      52643e8 | 2025-09-17 | Alex Kushleyev | fix bayer publish stride; enable publishing bayer images via shared ion buffers
      2a2c14d | 2025-09-17 | Alex Kushleyev | Merge branch 'dev' into fix-encoder-dynamic-low-bitrate
      dd7565a | 2025-09-16 | james | v2.2.7 remove voxl-cpu-monitor as build dependency and some general cleanups
      a435e8c | 2025-09-08 | Alex Kushleyev | enable low fps to be set dynamically without having it set in the camera config (less than 1.5mbps for h264 and less than 3.0mbps for h265
      272fe47 | 2025-09-03 | Alex Kushleyev | add a test colormap for boson using _color stream
      1d81a46 | 2025-08-21 | Alex Kushleyev | fix pipe json for AR0144 Color from YUV to RGB
      51afcb4 | 2025-08-21 | Alex Kushleyev | only read camera calibration if eis is enabled; add option to disable AWB on individual misp channels; add hooks for using RGB images instead of YUV for AWB
      1c3e99e | 2025-08-14 | Alex Kushleyev | add imx214 misp supported resolutions
      2390f20 | 2025-07-30 | modaljc | enable boson misp encoded by default instead of boson small encoded
      50a27ba | 2025-07-30 | Alex Kushleyev | Merge branch 'dev' of gitlab.com:voxl-public/voxl-sdk/services/voxl-camera-server into dev
      bbc9b89 | 2025-07-30 | Alex Kushleyev | add boson support to MISP; fix real-time fps control
      96c6a0d | 2025-07-22 | james | v2.2.5 fix stereo cam pair going out of sync due to too high of an allowed discrepancy
      055e11a | 2025-06-16 | Alex Kushleyev | clean up before merge to dev
      effc3e8 | 2025-06-12 | Alex Kushleyev | add eis params and minor cleanup
      

      @Alex-Kushleyev and modalai team, what can I do to fix that ?
      Let me know if you need additional logs or tests.
      Thanks in advence

      posted in Support Request Format for Best Results
      Q
      qt
    • RE: Poor GPS Fix

      Hello everyone,

      We’ve been following this discussion with great interest — especially the insights about the mast kit and the copper shielding solution. We also tried similar approaches on our side and wanted to share our results to contribute to the thread.

      We purchased four Starling 2 Max drones for our project at the beginning of the year, and like others here, we are experiencing difficulties with GPS stability outdoors. To mitigate interference, we designed and 3D-printed our own GPS mount to move the antenna away from the main body, and we added a copper shielding layer around it.

      We then tested the u-blox M10 GPS outside, under clear sky conditions, with the drone powered on (connected via Wi-Fi to use VOXL-Portal). Over about 10 minutes, the best observation we captured showed 18 satellites with an average SNR around 30–35 dB.
      vlcsnap-2025-07-25-14h33m43s700.png
      image474.png

      However, despite these results, we still cannot achieve a stable outdoor localization, which currently prevents us from flying the drones properly outside. At this point, we’re unsure whether the problem comes mainly from the GPS performance or possibly from the barometer.

      We’d really appreciate:

      • Being included in your support list for this GPS issue, since it affects multiple units on our side (as mentioned by @Alex-Kushleyev).
      • Any guidance or recommendations on how to debug further (extra shielding, hardware setup, barometer validation, software settings, etc.).

      Thanks a lot to the ModalAI team and to the community for the shared ideas — we hope our feedback helps others as well.

      Best regards,

      Quentin

      posted in PX4 Autonomy Developer Kit
      Q
      qt