ModalAI Forum
    • Categories
    • Recent
    • Tags
    • Popular
    • Users
    • Groups
    • Register
    • Login

    Hires cam not working with voxl2

    VOXL 2
    2
    14
    218
    Loading More Posts
    • Oldest to Newest
    • Newest to Oldest
    • Most Votes
    Reply
    • Reply as topic
    Log in to reply
    This topic has been deleted. Only users with topic management privileges can see it.
    • voxl-phoenixV
      voxl-phoenix
      last edited by voxl-phoenix

      I'm using a VOXL 2 flight controller with an M0173 Starling 2 Front End. The setup includes tracking camera, PMD TOF and a high-resolution (hires) IMX412 camera. While the tracking cameras and TOF are detected and functioning, I'm unable to get any response from the hires camera.

      I have tried reconnnecting camera again and reinstalled SDK. and downgraded to SDK 1.4.0.

      when I connected them first it worked properly and I havr disconnected the cable and connected again , it is not showing at all. I have checked reconnecting the cable properly multiple times. I even tried swapping Tracking cable to Hires but no use.

      Error I have got from voxl-camera-server

      fsync_en:            1
      fsync_gpio:          109
      =================================================================
      thread is locked to cores: 4 5 6 7
      connected to mavlink pipe
      Connected to cpu-monitor
      Starting Camera: tracking_front (id #0)
      gbm_create_device(156): Info: backend name is: msm_drm
      MISP Initializing!!!
       Detected 1 platform(s)
       Detected 1 GPU device(s)
      Starting Camera: hires (id #1)
      ERROR:   Camera 1 failed to find supported stream config: 1024x768
      WARNING: Failed to start cam hires due to invalid resolution
      WARNING: assuming cam is missing and trying to compensate
      Starting Camera: tof (originally id #2) with id offset: 1
      Starting Camera: tracking_down (originally id #3) with id offset: 1
      WARNING: cam tracking_down (id 2) does not seem to be alive
      
      ------ voxl-camera-server: Started 2 of 4 cameras
      
      ------ voxl-camera-server: Camera server is now running
      

      please suggest me any fixes for this.

      My SKU is :

      family code: MCCA-M0054 (voxl2-board-only)
      compute board: 4 (voxl2)
      hw version: 1
      cam config: 26
      modem config: ()
      tx config: ()
      extras config: ()
      SKU: MCCA-M0054-C26-T0-M0-X0

      this is my voxl-camera-server.config file

      cat /etc/modalai/voxl-camera-server.conf 
      /**
       * voxl-camera-server Configuration File
       *
       * Each camera has configurations for up to 4 HAL3 streams:
       *    - `preview` stream for raw unprocessed images from CV cameras
       *    - `small_video` 720p (ish) h264/h265 compressed for fpv video streaming
       *    - `large_video` 4k (ish) h264/h265 for onboard video recording to disk
       *    - `snapshot` ISP-processed JPG snapshots that get saved to disk
       *
       * on QRB5165 platforms (VOXL2 and VOXL2 mini) you can only have 3 of the 4 enabled
       *
       * This file is generated from default values by voxl-configure-cameras.
       * Do not expect arbitrary resolutions to work, the ISP and video compression
       * pipelines only support very specific resolutions.
       *
       * The default video compression mode is cqp or Constant Quantization Parameter
       *
       *
       *
       */
      {
      	"version":	0.1,
      	"fsync_en":	true,
      	"fsync_gpio":	109,
      	"cameras":	[{
      			"type":	"ar0144",
      			"name":	"tracking_front",
      			"enabled":	true,
      			"camera_id":	0,
      			"fps":	30,
      			"en_rotate":	true,
      			"en_preview":	true,
      			"preview_width":	1280,
      			"preview_height":	800,
      			"en_raw_preview":	true,
      			"en_misp":	true,
      			"misp_width":	1280,
      			"misp_height":	800,
      			"misp_venc_enable":	false,
      			"misp_venc_mode":	"h264",
      			"misp_venc_br_ctrl":	"cqp",
      			"misp_venc_Qfixed":	30,
      			"misp_venc_Qmin":	15,
      			"misp_venc_Qmax":	50,
      			"misp_venc_nPframes":	29,
      			"misp_venc_mbps":	2,
      			"misp_venc_osd":	false,
      			"misp_awb":	"auto",
      			"ae_mode":	"lme_msv",
      			"gain_min":	54,
      			"gain_max":	8000,
      			"ae_desired_msv":	60,
      			"exposure_min_us":	20,
      			"exposure_max_us":	12000,
      			"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":	"imx412",
      			"name":	"hires",
      			"enabled":	true,
      			"camera_id":	1,
      			"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,
      			"small_venc_osd":	false,
      			"en_large_video":	true,
      			"large_video_width":	4056,
      			"large_video_height":	3040,
      			"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,
      			"large_venc_osd":	false,
      			"en_snapshot":	true,
      			"en_snapshot_width":	4056,
      			"en_snapshot_height":	3040,
      			"exif_focal_length":	3.0999999046325684,
      			"exif_focal_length_in_35mm_format":	17,
      			"exif_fnumber":	1.2400000095367432,
      			"ae_mode":	"isp",
      			"gain_min":	54,
      			"gain_max":	8000
      		}, {
      			"type":	"pmd-tof-liow2",
      			"name":	"tof",
      			"enabled":	true,
      			"camera_id":	2,
      			"fps":	10,
      			"en_rotate":	true,
      			"ae_mode":	"off",
      			"gain_min":	0,
      			"gain_max":	0,
      			"exposure_max_us":	6000,
      			"standby_enabled":	false,
      			"decimator":	5
      		}, {
      			"type":	"ar0144",
      			"name":	"tracking_down",
      			"enabled":	true,
      			"camera_id":	3,
      			"fps":	30,
      			"en_rotate":	false,
      			"en_preview":	true,
      			"preview_width":	1280,
      			"preview_height":	800,
      			"en_raw_preview":	true,
      			"en_misp":	true,
      			"misp_width":	1280,
      			"misp_height":	800,
      			"misp_venc_enable":	false,
      			"misp_venc_mode":	"h264",
      			"misp_venc_br_ctrl":	"cqp",
      			"misp_venc_Qfixed":	30,
      			"misp_venc_Qmin":	15,
      			"misp_venc_Qmax":	50,
      			"misp_venc_nPframes":	29,
      			"misp_venc_mbps":	2,
      			"misp_venc_osd":	false,
      			"misp_awb":	"auto",
      			"ae_mode":	"lme_msv",
      			"gain_min":	54,
      			"gain_max":	8000,
      			"ae_desired_msv":	60,
      			"exposure_min_us":	20,
      			"exposure_max_us":	12000,
      			"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
      		}]
      }
      
      
      Alex KushleyevA 1 Reply Last reply Reply Quote 0
      • Alex KushleyevA
        Alex Kushleyev ModalAI Team @voxl-phoenix
        last edited by Alex Kushleyev

        @voxl-phoenix , if you use VOXL2 with the M0173 camera front-end, when you install the VOXL2 SDK, you need to select the option 2, which enables M0173:

        PLEASE SELECT WHICH KERNEL TO FLASH

        1. M0054-1 -> QRB5165M, Starling (D0005), Sentinel (D0006), FPV (D0008), D0010, PX4 Dev Kit (D0011)
        2. M0054-1 -> QRB5165M w/ M0173 Camera Breakout Board, Starling 2 Max (D0012), Starling 2 (D0014)

        The reason for this is the M0173 has different mapping of various GPIO that controls camera functions (including on/off). The camera GPIO control is done from the Kernel, so that is why a different kernel needs to be loaded if you use M0173.

        If you don't want to re-install the whole SDK, you can update the kernel manually:

        Test the new kernel without overwriting (will not persist after reboot):

        adb reboot bootloader
        fastboot boot m0054-1-var00.1-kernel.img
        

        Then you can adb into the board and do a quick test to see if all cameras are detected : voxl-camera-server -l will print at the top all detected cameras (in your case should be 4 cameras).

        To permanently flash the new kernel:

        adb reboot bootloader
        fastboot flash boot_a m0054-1-var00.1-kernel.img
        fastboot flash boot_b m0054-1-var00.1-kernel.img
        fastboot reboot
        

        (in order to flash the standard kernel, use m0054-1-var00.0-kernel.img)

        In order to check which kernel variant you are currently running:

        voxl2:/$ voxl-version | grep mach 
        mach.var:     1.0.0
        # this is the default kernel, not for use with M0173
        

        or

        voxl2:/$ voxl-version | grep mach
        mach.var:     1.0.1
        # this is the kernel for use with M0173
        

        If you are using M0154 (not M0054), It uses the same kernel as M0054, and will be detected as such.

        Hopefully this solves your issue.

        1 Reply Last reply Reply Quote 0
        • voxl-phoenixV
          voxl-phoenix
          last edited by

          @Alex-Kushleyev Thank you for the advise , I have been using the kernal image which includes M0173 breakout board.

          voxl2:~$ voxl-camera-server -l
          existing instance of voxl-camera-server found, attempting to stop it
          DEBUG:   Attempting to open the hal module
          DEBUG:   SUCCESS: Camera module opened on attempt 0
          DEBUG:   ----------- Number of cameras: 2
          
          DEBUG:   Cam idx: 0, Cam slot: 0, Slave Address: 0x0030, Sensor Id: 0x0356
          DEBUG:   Cam idx: 1, Cam slot: 3, Slave Address: 0x007A, Sensor Id: 0x2975
          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
          1280 x  800
          1280 x  800
          
          ANDROID_SCALER_AVAILABLE_STREAM_CONFIGURATIONS:
          These are NOT necessarily supported by the sensor
          1280 x  800 HAL_PIXEL_FORMAT_YCbCr_420_888
          1280 x  800 HAL_PIXEL_FORMAT_BLOB
          1280 x  768 HAL_PIXEL_FORMAT_YCbCr_420_888
          1280 x  768 HAL_PIXEL_FORMAT_BLOB
          1280 x  720 HAL_PIXEL_FORMAT_YCbCr_420_888
          1280 x  720 HAL_PIXEL_FORMAT_BLOB
          1024 x  738 HAL_PIXEL_FORMAT_YCbCr_420_888
          1024 x  738 HAL_PIXEL_FORMAT_BLOB
          1024 x  768 HAL_PIXEL_FORMAT_YCbCr_420_888
          1024 x  768 HAL_PIXEL_FORMAT_BLOB
           864 x  480 HAL_PIXEL_FORMAT_YCbCr_420_888
           864 x  480 HAL_PIXEL_FORMAT_BLOB
           800 x  600 HAL_PIXEL_FORMAT_YCbCr_420_888
           800 x  600 HAL_PIXEL_FORMAT_BLOB
           800 x  480 HAL_PIXEL_FORMAT_YCbCr_420_888
           800 x  480 HAL_PIXEL_FORMAT_BLOB
           720 x  480 HAL_PIXEL_FORMAT_YCbCr_420_888
           720 x  480 HAL_PIXEL_FORMAT_BLOB
           640 x  512 HAL_PIXEL_FORMAT_YCbCr_420_888
           640 x  512 HAL_PIXEL_FORMAT_BLOB
           640 x  480 HAL_PIXEL_FORMAT_YCbCr_420_888
           640 x  480 HAL_PIXEL_FORMAT_BLOB
           640 x  400 HAL_PIXEL_FORMAT_YCbCr_420_888
           640 x  400 HAL_PIXEL_FORMAT_BLOB
           640 x  360 HAL_PIXEL_FORMAT_YCbCr_420_888
           640 x  360 HAL_PIXEL_FORMAT_BLOB
           352 x  288 HAL_PIXEL_FORMAT_YCbCr_420_888
           352 x  288 HAL_PIXEL_FORMAT_BLOB
           320 x  240 HAL_PIXEL_FORMAT_YCbCr_420_888
           320 x  240 HAL_PIXEL_FORMAT_BLOB
           240 x  320 HAL_PIXEL_FORMAT_YCbCr_420_888
           240 x  320 HAL_PIXEL_FORMAT_BLOB
           176 x  144 HAL_PIXEL_FORMAT_YCbCr_420_888
           176 x  144 HAL_PIXEL_FORMAT_BLOB
          1280 x  800 HAL_PIXEL_FORMAT_RAW10
          1280 x  800 HAL_PIXEL_FORMAT_RAW12
          1280 x  800 HAL_PIXEL_FORMAT_RAW16
          1280 x  800 HAL_PIXEL_FORMAT_RAW_OPAQUE
          
          ANDROID_SENSOR_INFO_SENSITIVITY_RANGE
          	min = 54
          	max = 1596
          
          ANDROID_SENSOR_MAX_ANALOG_SENSITIVITY
          	1596
          
          ANDROID_SENSOR_INFO_EXPOSURE_TIME_RANGE
          	min = 0ns
          	max = 1318629735ns
          
          
          ====================================
          Stats for camera: 1
          
          ANDROID_SCALER_AVAILABLE_RAW_SIZES:
          These are likely supported by the sensor
           240 x 1629
          
          ANDROID_SCALER_AVAILABLE_STREAM_CONFIGURATIONS:
          These are NOT necessarily supported by the sensor
           240 x  320 HAL_PIXEL_FORMAT_YCbCr_420_888
           240 x  320 HAL_PIXEL_FORMAT_BLOB
           176 x  144 HAL_PIXEL_FORMAT_YCbCr_420_888
           176 x  144 HAL_PIXEL_FORMAT_BLOB
           240 x 1629 HAL_PIXEL_FORMAT_RAW10
           240 x 1629 HAL_PIXEL_FORMAT_RAW12
           240 x 1629 HAL_PIXEL_FORMAT_RAW16
           240 x 1629 HAL_PIXEL_FORMAT_RAW_OPAQUE
          
          ANDROID_SENSOR_INFO_SENSITIVITY_RANGE
          	min = 54
          	max = 0
          
          ANDROID_SENSOR_MAX_ANALOG_SENSITIVITY
          	0
          
          ANDROID_SENSOR_INFO_EXPOSURE_TIME_RANGE
          	min = 0ns
          	max = 0ns
          
          ====================================
          Number of cameras detected: 2
          ====================================
          voxl2:~$ voxl-version | grep mach
          mach.var:     1.0.1
          voxl2:~$ 
          
          

          I have TOF, tracking and Hires connected to the board it worked fine as soon as connected for first time than I can see no response from Hires but Tracking and TOF are working properly.

          Alex KushleyevA 1 Reply Last reply Reply Quote 0
          • Alex KushleyevA
            Alex Kushleyev ModalAI Team @voxl-phoenix
            last edited by

            @voxl-phoenix please make sure the cameras are connected as shown in C26 configuration https://docs.modalai.com/voxl2-coax-camera-bundles/

            voxl-phoenixV 1 Reply Last reply Reply Quote 0
            • voxl-phoenixV
              voxl-phoenix @Alex Kushleyev
              last edited by

              @Alex-Kushleyev
              Yeah I did follow the exact camera connections given on C26 configuration except that I don't have a down tracking camera. everything else is same. It's weird that it worked at start and than no response at all.

              Alex KushleyevA 1 Reply Last reply Reply Quote 0
              • Alex KushleyevA
                Alex Kushleyev ModalAI Team @voxl-phoenix
                last edited by Alex Kushleyev

                Can you please list
                /usr/lib/camera/*sensormodule*

                voxl-phoenixV 1 Reply Last reply Reply Quote 0
                • voxl-phoenixV
                  voxl-phoenix @Alex Kushleyev
                  last edited by voxl-phoenix

                  @Alex-Kushleyev

                  sorry for the trouble, but I can't get my head around why this is happening,

                  voxl2:~$ ls /usr/lib/camera/*sensormodule*
                  /usr/lib/camera/com.qti.sensormodule.ar0144_combo_0.bin
                  /usr/lib/camera/com.qti.sensormodule.ar0144_combo_6.bin
                  /usr/lib/camera/com.qti.sensormodule.imx412_fpv_1.bin
                  /usr/lib/camera/com.qti.sensormodule.irs2975c_3.bin
                  voxl2:~$
                  

                  is there any chance my SDK installation might be corrupt. I have tried using 1.4.1 and 1.4.0.

                  Alex KushleyevA 1 Reply Last reply Reply Quote 0
                  • Alex KushleyevA
                    Alex Kushleyev ModalAI Team @voxl-phoenix
                    last edited by

                    @voxl-phoenix , can you please confirm something - did you mention that this exact hardware setup was previously working with 4 cameras and now two cameras are no longer detected?

                    Regarding camera calibration, it seems the issue is that the calibrator is attempting to calibrate extrinsics (which is only done for a stereo camera setup), but you are only calibrating one camera. Let me look into that.

                    Alex

                    voxl-phoenixV 1 Reply Last reply Reply Quote 0
                    • voxl-phoenixV
                      voxl-phoenix @Alex Kushleyev
                      last edited by voxl-phoenix

                      @Alex-Kushleyev I have only three cameras one TOF, Tracking, Hires each. TOF and Tracking are working properly.

                      for calibration I',m just calibrating Tracking camera with fish eye

                      voxl-calibrate-cameras -f -s 8x5 -l 0.029
                      

                      it is trying to calibrate extrinsics automatically.

                      Alex KushleyevA 1 Reply Last reply Reply Quote 0
                      • Alex KushleyevA
                        Alex Kushleyev ModalAI Team @voxl-phoenix
                        last edited by

                        @voxl-phoenix ,

                        Ohh, sorry for the confusion. I misread your original post and thought that you have 4 cameras connected, like C26 configuration.

                        Can you please disconnect your M0173 from VOXL2 and take a picture showing the connectors on M0173 and where each camera is connected? just to double check.

                        Alex

                        voxl-phoenixV 1 Reply Last reply Reply Quote 0
                        • voxl-phoenixV
                          voxl-phoenix @Alex Kushleyev
                          last edited by voxl-phoenix

                          @Alex-Kushleyev

                          Thank you @Alex-Kushleyev
                          This is the output from my voxl-inspect-cam -a

                          |                Pipe Name |  bytes  | wide |  hgt |exp(ms)| gain | frame id |lt
                          |                 tof_conf |   43200 |  180 |  240 |  2.70 |    0 |     2824 | 8
                          |                tof_depth |   43200 |  180 |  240 |  2.70 |    0 |     2824 | 8
                          |                   tof_ir |   43200 |  180 |  240 |  2.70 |    0 |     2824 | 8
                          |           tracking_front | 1024000 | 1280 |  800 | 12.00 | 1596 |     8926 | 8
                          |     tracking_front_bayer | 1024000 | 1280 |  800 | 12.00 | 1596 |     8926 | 8
                          | tracking_front_misp_grey | 1024000 | 1280 |  800 | 12.00 | 1596 |     8926 | 8
                          | tracking_front_misp_norm | 1024000 | 1280 |  800 | 12.00 | 1596 |     8926 | 8
                          
                          

                          This is the output when I run voxl-camera-server.

                          voxl-camera-server 
                          existing instance of voxl-camera-server found, attempting to stop it
                          MISP awb str: auto
                          Setting MISP AWB to Autodetected system image 1.8.2
                          using new imx412 defaults
                          MISP awb str: auto
                          Setting MISP AWB to Auto=================================================================
                          configuration for 4 cameras:
                          
                          cam #0
                              name:                tracking_front
                              sensor type:         ar0144
                              isEnabled:           1
                              camId:               0
                              camId2:              -1
                              fps:                 30
                              en_rotate:           1
                              en_rotate2:          0
                          
                              en_preview:          1
                              pre_width:           1280
                              pre_height:          800
                              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_misp:             1
                              misp_width:          1280
                              misp_height:         800
                          
                              en_snapshot:         0
                              snap_width:          -1
                              snap_height:         -1
                              exif_focal_length:   0.000000
                              exif_focal_len_35mm_format:0
                              exif_fnumber:        0.000000
                          
                              ae_mode:             lme_msv
                              msv_exposure_min_us: 20
                              msv_exposure_max_us: 12000
                              gain_min           : 54
                              gain_max           : 8000
                              standby_enabled:     0
                              decimator:           1
                              independent_exposure:0
                          
                          cam #1
                              name:                hires
                              sensor type:         imx412
                              isEnabled:           1
                              camId:               1
                              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:   4056
                              large_video_height:  3040
                          
                              en_misp:             0
                              misp_width:          -1
                              misp_height:         -1
                          
                              en_snapshot:         1
                              snap_width:          4056
                              snap_height:         3040
                              exif_focal_length:   3.100000
                              exif_focal_len_35mm_format:17
                              exif_fnumber:        1.240000
                          
                              ae_mode:             isp
                              msv_exposure_min_us: 20
                              msv_exposure_max_us: 33000
                              gain_min           : 54
                              gain_max           : 8000
                              standby_enabled:     0
                              decimator:           1
                              independent_exposure:0
                          
                          cam #2
                              name:                tof
                              sensor type:         pmd-tof-liow2
                              isEnabled:           1
                              camId:               2
                              camId2:              -1
                              fps:                 10
                              en_rotate:           1
                              en_rotate2:          0
                          
                              en_preview:          1
                              pre_width:           240
                              pre_height:          1629
                              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_misp:             0
                              misp_width:          -1
                              misp_height:         -1
                          
                              en_snapshot:         0
                              snap_width:          -1
                              snap_height:         -1
                              exif_focal_length:   0.000000
                              exif_focal_len_35mm_format:0
                              exif_fnumber:        0.000000
                          
                              ae_mode:             off
                              msv_exposure_min_us: 0
                              msv_exposure_max_us: 6000
                              gain_min           : 0
                              gain_max           : 0
                              standby_enabled:     0
                              decimator:           5
                              independent_exposure:0
                          
                          cam #3
                              name:                tracking_down
                              sensor type:         ar0144
                              isEnabled:           1
                              camId:               3
                              camId2:              -1
                              fps:                 30
                              en_rotate:           0
                              en_rotate2:          0
                          
                              en_preview:          1
                              pre_width:           1280
                              pre_height:          800
                              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_misp:             1
                              misp_width:          1280
                              misp_height:         800
                          
                              en_snapshot:         0
                              snap_width:          -1
                              snap_height:         -1
                              exif_focal_length:   0.000000
                              exif_focal_len_35mm_format:0
                              exif_fnumber:        0.000000
                          
                              ae_mode:             lme_msv
                              msv_exposure_min_us: 20
                              msv_exposure_max_us: 12000
                              gain_min           : 54
                              gain_max           : 8000
                              standby_enabled:     0
                              decimator:           1
                              independent_exposure:0
                          
                          fsync_en:            1
                          fsync_gpio:          109
                          =================================================================
                          thread is locked to cores: 4 5 6 7
                          connected to mavlink pipe
                          Connected to cpu-monitor
                          Starting Camera: tracking_front (id #0)
                          gbm_create_device(156): Info: backend name is: msm_drm
                          MISP Initializing!!!
                           Detected 1 platform(s)
                           Detected 1 GPU device(s)
                          Starting Camera: hires (id #1)
                          ERROR:   Camera 1 failed to find supported stream config: 1024x768
                          WARNING: Failed to start cam hires due to invalid resolution
                          WARNING: assuming cam is missing and trying to compensate
                          Starting Camera: tof (originally id #2) with id offset: 1
                          Starting Camera: tracking_down (originally id #3) with id offset: 1
                          WARNING: cam tracking_down (id 2) does not seem to be alive
                          
                          ------ voxl-camera-server: Started 2 of 4 cameras
                          
                          ------ voxl-camera-server: Camera server is now running
                          camera tracking_front frame size: 1024000 (1540096 alloc).. raw bpp: 8
                          WARNING: [ROYALE_WARNING] {ROYALE_FRAME_DROP}: Dropped 10223 frame(s).
                          WARNING: [ROYALE_WARNING] {ROYALE_RAW_FRAME_STATS}: Raw frame drop stats: Bridge 10223 frames dropped, FC 0 frames dropped, 9 frames delivered.
                          WARNING: [ROYALE_WARNING] {ROYALE_FRAME_DROP}: Dropped 9 frame(s).
                          WARNING: [ROYALE_WARNING] {ROYALE_RAW_FRAME_STATS}: Raw frame drop stats: Bridge 9 frames dropped, FC 0 frames dropped, 81 frames delivered.
                          ^C
                          received SIGINT Ctrl-C
                          
                          ------ voxl-camera-server: Camera server is now stopping
                          WARNING: Deleting buffers: 6 of 16 still in use
                          WARNING: Deleting buffers: 6 of 16 still in use
                          
                          ------ voxl-camera-server: Camera server exited gracefully, returning 0
                          
                          
                          

                          this is my voxl sdk info

                          voxl2:~$ voxl-version 
                          --------------------------------------------------------------------------------
                          system-image: 1.8.02-M0054-14.1a-perf
                          kernel:       #1 SMP PREEMPT Mon Nov 11 22:47:44 UTC 2024 4.19.125
                          --------------------------------------------------------------------------------
                          hw platform:  M0054
                          mach.var:     1.0.1
                          --------------------------------------------------------------------------------
                          voxl-suite:   1.4.3
                          --------------------------------------------------------------------------------
                          Packages:
                          
                          

                          5459cf57-ddf0-4dc7-9473-e57c44cde652-image.png

                          d0567585-033c-4f56-a57a-d6954b50c545.jpeg

                          Thank you for help.

                          Alex KushleyevA 1 Reply Last reply Reply Quote 0
                          • Alex KushleyevA
                            Alex Kushleyev ModalAI Team @voxl-phoenix
                            last edited by

                            @voxl-phoenix , the connections look correct. Can you please clarify whether this setup was working (hires camera was working) and then suddenly stopped working? Or what changed between the time when it was working and now.

                            Alex

                            voxl-phoenixV 1 Reply Last reply Reply Quote 0
                            • voxl-phoenixV
                              voxl-phoenix @Alex Kushleyev
                              last edited by

                              @Alex-Kushleyev I have got this camera two days back and I have connected it and tested them both they, worked fine. I had to unbrick my board so I unbricked it and installed new SDK 1.4.1.

                              It was working fine before and after installation. I have just disconnected the camera and conected it again, because I was installing it in the holder that I 3D printed, just before installing I have tested it once, it is not working since than. only once I have disconnected the cable and connected it again, it stopped working. I have checked there is no damage to cables or board. I have handled them properly.

                              Alex KushleyevA 1 Reply Last reply Reply Quote 0
                              • Alex KushleyevA
                                Alex Kushleyev ModalAI Team @voxl-phoenix
                                last edited by

                                @voxl-phoenix , I think you also mentioned that you tried swapping the cables between tracking and imx412 camera, right? If so, it seems something got damaged in the IMX412 camera during connecting / disconnecting. For disconnecting the cables, we suggest using a special tool, please see https://docs.modalai.com/micro-coax-user-guide/#-proper-cable-and-adapter-handling- .

                                Also, it is hard to say for sure where exactly the issue is - M0173 board or IMX412 camera. the only good way find the cause is to replace components one at a time.

                                Just to elaborate on the symptoms that you are seeing : voxl-camera-server -l command essentially probes all the cameras (based on the sensormodule files located in /usr/lib/camera). Probing involves turning the camera on via the reset GPIO and attempting to talk to the camera via I2c interface. If the camera responds, the probe is successful, otherwise failed. In your case, the probe of IMX412 failed, which means either the camera could not be turned on for various reasons or the i2c communication was not working.

                                If you have another tracking camera AR0144, you could connect it instead of the IMX412 and see if the probe succeeds. You would need to add /usr/share/modalai/chi-cdk/ar0144/com.qti.sensormodule.ar0144_1.bin file to /usr/lib/camera (which is the AR0144 sensormodule for the camera slot 1, where the IMX412 is currently connected). Then if you run voxl-camera-server -l and detect two AR0144 cameras (3 cameras total) then i2c communication and power should be working).

                                Alex

                                1 Reply Last reply Reply Quote 0
                                • First post
                                  Last post
                                Powered by NodeBB | Contributors