maplab icon indicating copy to clipboard operation
maplab copied to clipboard

Down Facing Camera (ZR300)

Open bsbretly opened this issue 6 years ago • 4 comments

Hello, I have the following setup on my MAV - I'm running rovioli in VIO mode with a down facing ZR300 camera and IMU. Using your maplab_realsense package for the ZR300, I've noticed that the ZR300 IMU publishes no orientation data, i.e. the quaternion is always [0 0 0 0]. As such, I imagine all orientation data for pose estimation within rovioli must come from the feature descriptors. Is this true?

If so, I'm confused as to why I'm experiencing the following problem: when I launch rovioli with the camera downward, the orientation of the pose estimated by rovioli seems to be initialized randomly. However, when I orient my MAV such that the camera is facing forward (or any other direction besides downward in fact), I am able to get rovioli to initialize a pose with consistent orientation. This phenomenon is causing me issues later down my pipeline where I am attempting to fuse the rovioli pose with another IMU using your ethz_msf package.

Do you have any insights into why this is occurring?

Your help is much appreciated!

bsbretly avatar Jul 10 '18 08:07 bsbretly

Hi @bsbretly

  • Missing orientation in realsense IMU message: This is perfectly fine, some IMUs/Sensors come with an existing estimation solution and therefore publish an orientation as part of their IMU message. However the ZR300 doesn't have this feature, and it's also not required by ROVIO(LI). ROVIO estimates the pose of the sensor based on both images and Imu data (linear acceleration and rotational rates).
  • Down facing initialization: There are many reasons why this doesn't work (well), so we can only speculate. If you provide us with a rosbag + calibration we might be able to help:
    • If the camera faces the floor there might not be any features for the filter to initialize properly.
    • The way ROVIO is initializing the features is tuned for the normal/front-facing indoor use-case, that's why it might struggle if all features are very close to the camera. These parameters can be tuned though.

mfehr avatar Jul 10 '18 10:07 mfehr

Hi @mfehr,

Thanks for the quick response!

  • Down facing inititialization:
    • I've ensured that there are plenty of features to detect with my downward facing camera by placing an apriltag grid below the camera, so I don't think lack of features is an issue.
    • Your point on the distance of the features relative to camera may be a an issue, as my camera is initialized about 8cm from the ground. I will try to initialize with features at a larger distance and post the results.

I would also be happy to send over a rosbag - are there any other topics you would be interested in besides the ZR300 fisheye raw image and the IMU data?

bsbretly avatar Jul 10 '18 11:07 bsbretly

One possibile explanation is that from memory Rovio initializes itself so that z is in the gravity direction and x is the direction the camera is facing. This means that if the camera is pointing in the same direction as gravity which direction it takes to be forwards is a bit arbitrary and will mainly depend on the noise in the system.

ZacharyTaylor avatar Jul 10 '18 11:07 ZacharyTaylor

@ZacharyTaylor - interesting, I think this could very well be the issue. I will verify this soon, but if my memory is correct, I think I'm experiencing this issue independent of how far the features are from the camera when initialized.

I'm considering two possible solutions at this point

  1. Remounting my camera so that it's cardinal orientation is not aligned with gravity.
  2. More of a "patch" than a fix, but writing a node that calculates the initial yaw offset between my world frame and state frame and ensures they are aligned.

Any other suggestions or potential issues with my above solutions are appreciated.

bsbretly avatar Jul 10 '18 11:07 bsbretly