Cannot connect to cameras on VOXL Flight, voxl-camera-server crashes
-
I upgraded the system image to SDK1.2, as it is the latest supported for VOXL Flight (I have a beta version of the Starling drone):
voxl-version -------------------------------------------------------------------------------- system-image: 4.0.0 kernel: #1 SMP PREEMPT Thu Oct 13 17:57:05 UTC 2022 3.18.71-perf -------------------------------------------------------------------------------- hw platform: VOXL mach.var: 1.0 -------------------------------------------------------------------------------- voxl-suite: 1.2.0 -------------------------------------------------------------------------------- Packages: Repo: http://voxl-packages.modalai.com/dists/apq8096/sdk-1.2/binary-arm64/ Last Updated: Never List: apq8096-dfs-server 0.3.1 apq8096-imu-server 1.1.0 apq8096-libpng 1.6.38-1 apq8096-rangefinder-server 0.1.3 apq8096-system-tweaks 0.2.3 apq8096-tflite 2.8.3-1 libapq8096-io 0.6.1 libmodal-cv 0.4.0 libmodal-exposure 0.1.0 libmodal-journal 0.2.2 libmodal-json 0.4.3 libmodal-pipe 2.10.0 libvoxl-cci-direct 0.2.1 libvoxl-cutils 0.1.1 voxl-camera-calibration 0.5.4 voxl-camera-server 1.9.2 voxl-configurator 0.5.6 voxl-cpu-monitor 0.4.8 voxl-docker-support 1.3.1 voxl-gphoto2-server 0.0.10 voxl-jpeg-turbo 2.1.3-5 voxl-lepton-server 1.2.0 voxl-libgphoto2 0.0.4 voxl-libuvc 1.0.7 voxl-logger 0.4.0 voxl-mavcam-manager 0.5.3 voxl-mavlink 0.1.1 voxl-mavlink-server 1.4.0 voxl-modem 1.0.9 voxl-mongoose 7.7.0-1 voxl-mpa-to-ros 0.3.7 voxl-mpa-tools 1.1.5 voxl-opencv 4.5.5-2 voxl-portal 0.6.5 voxl-qvio-server 1.0.2 voxl-remote-id 0.0.9 voxl-streamer 0.7.4 voxl-suite 1.2.0 voxl-system-image 4.0-r0 voxl-tag-detector 0.0.4 voxl-tflite-server 0.3.2 voxl-utils 1.3.9 voxl-uvc-server 0.1.6 voxl-vision-hub 1.7.4 voxl-vpn 0.0.6 --------------------------------------------------------------------------------
The cameras were working fine up until recently and I did not attempt to modify any hardware. The following cameras are connected to VOXL Flight (connectors) :
- tracking (port J4)
- hires (port J2)
- tof (port J3)
(left unaltered as provided by ModalAI)
I performed the following setup after flashing the image:
voxl-configure-cameras 6 # Hires + TOF + Tracking voxl-configure-extrinsics starling_v1_voxl_flight voxl-configure-qvio factory_enable_imu0 # for VOXL Flight all-in-one board.
Which yielded the following extrinsics:
voxl-inspect-extrinsics #0: parent: imu1 child: imu0 T_child_wrt_parent: -0.048 0.037 0.002 RPY_parent_to_child: 0.0 0.0 0.0 R_child_to_parent: 1.000 -0.000 0.000 0.000 1.000 -0.000 0.000 0.000 1.000 #1: parent: imu0 child: tracking T_child_wrt_parent: 0.060 -0.014 0.011 RPY_parent_to_child: 0.0 45.0 90.0 R_child_to_parent: 0.000 -0.707 0.707 1.000 0.000 -0.000 -0.000 0.707 0.707 #2: parent: imu1 child: tracking T_child_wrt_parent: 0.012 0.015 0.013 RPY_parent_to_child: 0.0 45.0 90.0 R_child_to_parent: 0.000 -0.707 0.707 1.000 0.000 -0.000 -0.000 0.707 0.707 #3: parent: body child: imu0 T_child_wrt_parent: 0.000 0.014 -0.008 RPY_parent_to_child: 0.0 0.0 0.0 R_child_to_parent: 1.000 -0.000 0.000 0.000 1.000 -0.000 0.000 0.000 1.000 #4: parent: body child: imu1 T_child_wrt_parent: 0.049 -0.015 -0.011 RPY_parent_to_child: 0.0 0.0 0.0 R_child_to_parent: 1.000 -0.000 0.000 0.000 1.000 -0.000 0.000 0.000 1.000 #5: parent: body child: stereo_l T_child_wrt_parent: 0.065 -0.040 0.000 RPY_parent_to_child: 0.0 90.0 90.0 R_child_to_parent: 0.000 -0.000 1.000 1.000 0.000 -0.000 -0.000 1.000 0.000 #6: parent: body child: tof T_child_wrt_parent: 0.065 -0.013 0.010 RPY_parent_to_child: 0.0 90.0 90.0 R_child_to_parent: 0.000 -0.000 1.000 1.000 0.000 -0.000 -0.000 1.000 0.000 #7: parent: body child: ground T_child_wrt_parent: 0.000 0.000 0.029 RPY_parent_to_child: 0.0 0.0 0.0 R_child_to_parent: 1.000 -0.000 0.000 0.000 1.000 -0.000 0.000 0.000 1.000
Listing plugged in camera with
voxl-camera-server -l
returns:DEBUG: Attempting to open the hal module DEBUG: SUCCESS: Camera module opened on attempt 0 DEBUG: ----------- Number of cameras: 2 DEBUG: Note: This list comes from the HAL module and may not be indicative DEBUG: of configurations that have full pipelines DEBUG: Number of cameras: 2 ==================================== Stats for camera: 0 ANDROID_SCALER_AVAILABLE_RAW_SIZES: These are likely supported by the sensor 4208 x 3120 4096 x 2160 2104 x 1560 1920 x 1080 1280 x 720 2104 x 1506 ANDROID_SCALER_AVAILABLE_STREAM_CONFIGURATIONS: These are NOT necessarily supported by the sensor 4208 x 3120 HAL_PIXEL_FORMAT_RAW_OPAQUE ... ANDROID_SENSOR_INFO_SENSITIVITY_RANGE min = 41 max = 3987 ANDROID_SENSOR_MAX_ANALOG_SENSITIVITY 332 ANDROID_SENSOR_INFO_EXPOSURE_TIME_RANGE min = 20678ns max = 683881516ns ==================================== Stats for camera: 1 ANDROID_SCALER_AVAILABLE_RAW_SIZES: These are likely supported by the sensor 640 x 480 320 x 240 ANDROID_SCALER_AVAILABLE_STREAM_CONFIGURATIONS: These are NOT necessarily supported by the sensor 640 x 480 HAL_PIXEL_FORMAT_RAW_OPAQUE ... ANDROID_SENSOR_INFO_SENSITIVITY_RANGE min = 100 max = 6399 ANDROID_SENSOR_MAX_ANALOG_SENSITIVITY 6399 ANDROID_SENSOR_INFO_EXPOSURE_TIME_RANGE min = 19425ns max = 1020461640ns ==================================== Number of cameras detected: 2 ====================================
Trying to run
voxl-camera-server -d 0
generates:WARNING Failed to set priority, errno = 1 This may be because the FIFO scheduler is not available when running in a console. It should work properly when run as a systemd background process on boot. WARNING: failed to set scheduler using new imx214 defaults ================================================================= configuration for 3 cameras: cam #0 name: tracking sensor type: ov7251 isEnabled: 1 camId: 2 camId2: -1 fps: 30 en_rotate: 0 en_rotate2: 0 en_preview: 1 pre_width: 640 pre_height: 480 en_raw_preview: 1 en_small_video: 0 small_video_width: -1 small_video_height: -1 en_large_video: 0 large_video_width: -1 large_video_height: -1 en_snapshot: 0 snap_width: -1 snap_height: -1 ae_mode: lme_msv standby_enabled: 0 decimator: 1 independent_exposure:0 cam #1 name: tof sensor type: pmd-tof isEnabled: 1 camId: 1 camId2: -1 fps: 5 en_rotate: 0 en_rotate2: 0 en_preview: 1 pre_width: 224 pre_height: 1557 en_raw_preview: 1 en_small_video: 0 small_video_width: -1 small_video_height: -1 en_large_video: 0 large_video_width: -1 large_video_height: -1 en_snapshot: 0 snap_width: -1 snap_height: -1 ae_mode: off standby_enabled: 0 decimator: 5 independent_exposure:0 cam #2 name: hires sensor type: imx214 isEnabled: 1 camId: 0 camId2: -1 fps: 30 en_rotate: 0 en_rotate2: 0 en_preview: 0 pre_width: 640 pre_height: 480 en_raw_preview: 0 en_small_video: 1 small_video_width: 1024 small_video_height: 768 en_large_video: 1 large_video_width: 1920 large_video_height: 1080 en_snapshot: 1 snap_width: 4160 snap_height: 3120 ae_mode: isp standby_enabled: 0 decimator: 1 independent_exposure:0 fsync_en: 0 fsync_gpio: 111 ================================================================= DEBUG: Attempting to open the hal module DEBUG: SUCCESS: Camera module opened on attempt 0 DEBUG: ----------- Number of cameras: 2 DEBUG: ------ voxl-camera-server: Starting 3 cameras Starting Camera: tracking (id #2) WARNING: cam tracking (id 2) does not seem to be alive Starting Camera: tof (id #1) DEBUG: Checking Gain limits for Camera: tof Using gain limits min: 100 max: 6399 DEBUG: cam ID 1 checking for fmt: 33 w: 224 h: 1557 o: 0 DEBUG: ==> option 0: format= 36 width= 640 height= 480 is_input=0 DEBUG: ==> option 4: format= 36 width= 320 height= 240 is_input=0 DEBUG: ==> option 8: format= 32 width= 640 height= 480 is_input=0 DEBUG: ==> option 12: format= 32 width= 320 height= 240 is_input=0 DEBUG: ==> option 16: format= 35 width= 640 height= 480 is_input=0 DEBUG: ==> option 20: format= 35 width= 640 height= 240 is_input=0 DEBUG: ==> option 24: format= 35 width= 640 height= 360 is_input=0 DEBUG: ==> option 28: format= 35 width= 480 height= 480 is_input=0 DEBUG: ==> option 32: format= 35 width= 480 height= 360 is_input=0 DEBUG: ==> option 36: format= 35 width= 480 height= 320 is_input=0 DEBUG: ==> option 40: format= 33 width= 640 height= 480 is_input=0 DEBUG: ==> option 44: format= 33 width= 640 height= 240 is_input=0 DEBUG: ==> option 48: format= 33 width= 640 height= 360 is_input=0 DEBUG: ==> option 52: format= 33 width= 480 height= 480 is_input=0 DEBUG: ==> option 56: format= 33 width= 480 height= 360 is_input=0 DEBUG: ==> option 60: format= 33 width= 480 height= 320 is_input=0 DEBUG: ==> option 64: format= 37 width= 640 height= 480 is_input=0 DEBUG: ==> option 68: format= 37 width= 320 height= 240 is_input=0 DEBUG: ==> option 72: format= 38 width= 640 height= 480 is_input=0 DEBUG: ==> option 76: format= 38 width= 320 height= 240 is_input=0 DEBUG: ==> option 80: format= 34 width= 640 height= 480 is_input=0 DEBUG: ==> option 84: format= 34 width= 640 height= 240 is_input=0 DEBUG: ==> option 88: format= 34 width= 640 height= 360 is_input=0 DEBUG: ==> option 92: format= 34 width= 480 height= 480 is_input=0 DEBUG: ==> option 96: format= 34 width= 480 height= 360 is_input=0 DEBUG: ==> option 100: format= 34 width= 480 height= 320 is_input=0 ERROR: Camera 1 failed to find supported preview config: 224x1557 WARNING: Failed to start cam tof due to invalid resolution WARNING: assuming cam is missing and trying to compensate Starting Camera: hires (originally id #0) with id offset: 1 WARNING: cam hires (id -1) does not seem to be alive ERROR: failed to initialize any cameras ------ voxl-camera-server: Started 0 of 3 cameras ------ voxl-camera-server: Camera server is now running ------ voxl-camera-server: Camera server is now stopping DEBUG: Erasing all managers ------ voxl-camera-server: Camera server exited gracefully, returning -1
Finally, here is the camera server configuration (
/etc/modalai/voxl-camera-server.conf
) :{ "version": 0.1, "fsync_en": false, "fsync_gpio": 111, "cameras": [{ "type": "ov7251", "name": "tracking", "enabled": true, "camera_id": 2, "fps": 30, "en_rotate": false, "en_preview": true, "preview_width": 640, "preview_height": 480, "en_raw_preview": true, "ae_mode": "lme_msv", "ae_desired_msv": 60, "exposure_min_us": 20, "exposure_max_us": 33000, "gain_min": 54, "gain_max": 8000, "exposure_soft_min_us": 5000, "ae_filter_alpha": 0.600000023841858, "ae_ignore_fraction": 0.20000000298023224, "ae_slope": 0.05000000074505806, "ae_exposure_period": 1, "ae_gain_period": 1 }, { "type": "pmd-tof", "name": "tof", "enabled": true, "camera_id": 1, "fps": 5, "ae_mode": "off", "standby_enabled": false, "decimator": 5 }, { "type": "imx214", "name": "hires", "enabled": true, "camera_id": 0, "fps": 30, "en_preview": false, "preview_width": 640, "preview_height": 480, "en_raw_preview": false, "en_small_video": true, "small_video_width": 1024, "small_video_height": 768, "small_venc_mode": "h264", "small_venc_br_ctrl": "cqp", "small_venc_Qfixed": 30, "small_venc_Qmin": 15, "small_venc_Qmax": 40, "small_venc_nPframes": 9, "small_venc_mbps": 2, "en_large_video": true, "large_video_width": 1920, "large_video_height": 1080, "large_venc_mode": "h264", "large_venc_br_ctrl": "cqp", "large_venc_Qfixed": 40, "large_venc_Qmin": 15, "large_venc_Qmax": 50, "large_venc_nPframes": 29, "large_venc_mbps": 40, "en_snapshot": true, "en_snapshot_width": 4160, "en_snapshot_height": 3120, "ae_mode": "isp" }] }
I doubt all cameras are dead... I can actually run the server with only hires by setting the enabled field to false in the camera server config. Could this be linked to some hardware/software version mismatch of the expected camera types? Any pointers as to how to address this issue would be much appreciated!
Edit: a similar issue has been raised before, see this post, but no solution was given.
-
I tried swapping the tof camera with a spare one I had around. The spare tof worked immediately without issue. I then disconnected the spare tof, configured the camera server with only hires and tracking (with no connected tof camera, which worked fine). I then tried to plug back in the original tof and it started working again. So nothing changed, just unplugged and plugged back the tof camera and reflected the changes by configuring the camera server accordingly, weird...