Stereo Camera Orientation
-
I have an inverted custom setup where my OV7251 stereo cameras are mounted upside-down, as pictured below.
Setup Diagram: (By the way, is this really how L/R pairs are? Seems weird to me. I concluded this based on error responses I got from the calibration process.)
Strangely, in the web portal, my stereo_front camera feeds display as being right-side up, while my stereo_rear camera feeds are flipped upside-down.
Conversely, when I look at my voa_pc_out pointcloud, the cloud coming from the stereo_front cameras appears to be inverted and the stereo_rear cameras appear to be oriented correctly (matching what I expect based on the VOXL2 board's reference frame).
This leads me to think that my stereo_rear cameras are actually configured correctly. The image outputs are upside-down because that's what they are in reality, and the vision-hub is correctly processing that based on the configured extrinsics to output a correctly oriented pointcloud.
My Extrinsics File:
I've looked over my extrinsics file a few times to look for rotation matrix errors, but I don't see anything wrong and it passes the camera calibration process with flying colors. Am I missing something?
I also looked and found this thread from a few weeks ago that instructs on swapping some files in /usr/bin/camera that might fix my problem. However, I still have confusion due to my front and rear stereo pairs exhibiting different behavior. Should I replace all my com.qti.sensor.ov7251_combo files with their _flip alternates or just the ones related to my front or rear stereo pair?
After I swap files, I'm guessing that I then need to redo the rotation matrixes related to that stereo pair?
My /usr/lib/camera directory:
Any help here is extremely appreciated. I can give more details as well. Thank you!
-
@MattK , can you please do a quick check in your
/etc/modalai/voxl-camera-server.conf
and see if any of your stereo pairs are set to be rotated in software? Specifically, look for:"en_rotate": true, "en_rotate_second": true,
I believe this is your issue.
if the rotate flag is set, this will cause the camera server to send a special command to the cameras to rotate the images (in the camera). code here. The cameras don't actually rotate the image, but the "readout direction" is reversed, so image is sent out instead of starting at top left, bottom right instead.
if you use
combo-flip
sensormodules and seten_rotate
to false in camera server config, this will achieve exactly the same effect as non-flip sensormodules anden_rotate
set to true.Please note that if you rotate the image in the camera this way, you need to re-do the camera intrinsic calibration because the rotation will shift the principal points.
Once you undo the rotation on your front stereo, you should not have to re-do your extrinsics computations (w.r.t body) if you already did it assuming the cameras are right side up (you will simply be making the image consistent with your prior assumption of being right side up).
Alex
-
@Alex-Kushleyev you were right! The stereo_front pair did have
en_rotate
set to true. Thanks! -
-
I am curious what the convention would be for both extrinsics and camera server configs if you have stereo cameras that need to be rotated 90 degrees
-
@Gary-Holmgren , camera server does not support rotating images by 90 degrees (or multiples of 90). You could do this yourself in your image processing application.
If you mount the cameras rotated by 90 degrees (while keeping the baseline along the left-right direction of the drone), you would need to modify your extrinsics to account for this rotation. If you perform a stereo camera calibration in this rotated configuration, then the output of the stereo calibration should give you the baseline result between the cameras in the Y direction in the camera frame (as opposed to X direction in normal case).
If you have a question about a specific configuration, please make a drawing that shows reference frames of the vehicle, imu, and both cameras and I can help you double check the extrinsics.
Alex