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

    Poor performance with vertical oriented tracking camera

    GPS-denied Navigation (VIO)
    2
    6
    439
    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.
    • J
      Jeremy Frederick
      last edited by 7 May 2024, 17:41

      For a project I'm working on, we need to operate the tracking camera facing directly up or 45 degrees vertical (from forward facing). In either orientation, the tracking camera is able to pick up significant points but cannot seem to get a quality higher then 1-5% causing poor VIO performance. I've set the extrinsic file, when the camera is pointed 45 degrees up from forward facing, to be RPY( 0, 270, 90). Is this correct?

      A 1 Reply Last reply 7 May 2024, 19:21 Reply Quote 0
      • A
        Alex Kushleyev ModalAI Team @Jeremy Frederick
        last edited by Alex Kushleyev 7 May 2024, 19:21 7 May 2024, 19:21

        @Jeremy-Frederick ,

        If you are looking for a transformation from the body frame (X=forward, Y=right, Z=down) into the camera frame that is looking straight out and then just pointed up 45 degrees, you will have the following transformation:

        (0, 135, 90)

        roll 0, pitch 135 to bring Z axis from pointing down to pointing up 45 degrees, then yaw 90 around the new Z axis degrees so that X axis points to the right.

        I think i got that right.. hopefully this helps!

        J 1 Reply Last reply 7 May 2024, 23:14 Reply Quote 0
        • J
          Jeremy Frederick @Alex Kushleyev
          last edited by Jeremy Frederick 7 May 2024, 23:16 7 May 2024, 23:14

          @Alex-Kushleyev This is very helpful. My major issue however is a lack of quality for which I am struggling to understand,Quality1.png

          This is using the Voxl 2 Mini, SDK 1.1.3 with the OV7251 sensor. Other platforms I've built with this sensor have no issues maintaining over 50% quality in this environment (albeit on the full VOXL 2, this is my first time using the mini). It also seems to have issues with the calibration, I've already replaced the tracking sensor with no change. The quality of the picture is equivalent to what I'd expect as well. Tomorrow I am going to try and upgrade to SDK 1.2 to see if there is a difference.

          A 1 Reply Last reply 8 May 2024, 03:41 Reply Quote 0
          • A
            Alex Kushleyev ModalAI Team @Jeremy Frederick
            last edited by 8 May 2024, 03:41

            @Jeremy-Frederick , if you suspect that may be multiple issues going on here, i would recommend to turn the camera back to the standard orientation and use standard params that we support and make sure that VIO is working well. After you confirm that, turn the camera back up to 45 degrees and update the transform and test again. If the performance suddenly goes from good to bad, then there is still something wrong with the transform and we can look at that..

            J 1 Reply Last reply 8 May 2024, 21:33 Reply Quote 0
            • J
              Jeremy Frederick @Alex Kushleyev
              last edited by 8 May 2024, 21:33

              @Alex-Kushleyev Alex, looks like the issue was due to the mini being mounted upside down, and me failing to set that correctly in the extrinsic configuration file. I set the body - imu_apps to expect an 180 degree roll configuration and that solved my issue. The core of which ended up being that the voxl-vision-hub service was reading the system as upside down and therefore resetting the service every few seconds, causing the issue.

              Is this the correct way to report the flight controller being upside down to the vision service? I've already confirmed the tracking sensor to IMU relation is correct. My edit seems to work, but I want to make sure it is correct.

              A 1 Reply Last reply 9 May 2024, 15:30 Reply Quote 0
              • A
                Alex Kushleyev ModalAI Team @Jeremy Frederick
                last edited by 9 May 2024, 15:30

                @Jeremy-Frederick , If VIO is working, then there is a very high chance that you got the orientation correct 🙂 . If the camera to IMU orientation is off by something like 90 degrees in any direction, VIO is pretty much guaranteed to fail. So if you are getting normal VIO performance, quick initialization, across multiple tests, then I would say that your orientation parameters are correct for VIO.

                Please keep in mind that if you flipped the board and if you are planning to fly with PX4, you will need to change the imu rotation params in PX4 (also keep in mind that PX4 is using a different IMU that is connected to the DSP)

                1 Reply Last reply Reply Quote 0
                1 out of 6
                • First post
                  1/6
                  Last post
                Powered by NodeBB | Contributors