-
Notifications
You must be signed in to change notification settings - Fork 120
Home
Xivo is a filtering-based visual-inertial odometry (VIO) system. At its core, Xivo is an Extended Kalman Filter (EKF) with additional image processing and mapping capabilities. A diagram of its components is shown below.
IMU measurements are implemented as model inputs. EKF State Prediction
occurs whenever a new IMU measurement is acquired, typically at a frequency of hundreds of Hz. Pixel coordinates of tracked features are sensor measurements. EKF Measurement Prediction
, Image Processing
, and EKF Measurement Update
occur whenever a new RGB image is acquired, typically at a frequency of dozens of Hz. Mapping
searches for loop closures and solves the bundle adjustment problem in the background.
- Spatial/world frame (
$s$ ) - A static frame that is never moving. For issues related to observability, it is fixed to be the position and orientation of the IMU at startup. - Body/IMU frame (
$b$ ) - A frame attached to the IMU. The exact direction of the axes are determined by the manufacturer and how the IMU is mounted. - Camera frame (
$c$ ) - A frame attached to the camera's pinhole. The$Z$ axis points outward perpendicular to the image plane. The$X$ axis is ... - Gravity frame (
$g$ ) - A frame that is aligned with gravity and co-located with the Body frame. In this frame, gravitational acceleration has value$[0, 0, -9.8]^T$ .
Please see this document for a detailed description.
Xivo is implemented in C++ in an object-oriented paradigm. A list of objects is shown below. Major components, shown in blue boxes, are singletons. The map is a collection of Feature
and Group
(past poses at times RGB images were taken) objects created by the MemoryManager
and accessible through the Graph
.
Each Group
contains pointers to all the features that were visible in the RGB image at that time. One group, designated the Reference Group
(a.k.a. Gauge Group
), is fixed -- the filter estimates positions and orientations relative to relative to the Reference Group
until all features the Reference Group
points to are no longer visible. When all features the Reference Group
points to are no longer visible, the group with visible features and the smallest covariance is the new reference group.