ov_msckf namespace

Contents

This is an implementation of a Multi-State Constraint Kalman Filter (MSCKF) [12] which leverages inertial and visual feature information. We want to stress that this is not a "vanilla" implementation of the filter and instead has many more features and improvements over the original. In additional we have a modular type system which allows us to initialize and marginalizing variables out of state with ease. Please see the following documentation pages for derivation details:

The key features of the system are the following:

  • Sliding stochastic imu clones
  • First estimate Jacobians
  • Camera intrinsics and extrinsic online calibration
  • Time offset between camera and imu calibration
  • Standard MSCKF features with nullspace projection
  • 3d SLAM feature support (with six different representations)
  • Generic simulation of trajectories through and environment (see ov_msckf::Simulator)

We suggest those that are interested to first checkout the State and Propagator which should provide a nice introduction to the code. Both the slam and msckf features leverage the same Jacobian code, and thus we also recommend looking at the UpdaterHelper class for details on that.

Classes

class Propagator
Performs the state covariance and mean propagation using imu measurements.
class RosVisualizer
Helper class that will publish results onto the ROS framework.
class Simulator
Master simulator class that generated visual-inertial measurements.
class State
State of our filter.
class StateHelper
Helper which manipulates the State and its covariance.
struct StateOptions
Struct which stores all our filter options.
class UpdaterHelper
Class that has helper functions for our updaters.
class UpdaterMSCKF
Will compute the system for our sparse features and update the filter.
struct UpdaterOptions
Struct which stores general updater options.
class UpdaterSLAM
Will compute the system for our sparse SLAM features and update the filter.
class UpdaterZeroVelocity
Will try to detect and then update using zero velocity assumption.
class VioManager
Core class that manages the entire system.
struct VioManagerOptions
Struct which stores all options needed for state estimation.

Functions

auto parse_command_line_arguments(int argc, char** argv) -> VioManagerOptions
This function will parse the command line arugments using CLI11. This is only used if you are not building with ROS, and thus isn't the primary supported way to pass arguments. We recommend building with ROS as compared using this parser.
auto parse_ros_nodehandler(ros::NodeHandle& nh) -> VioManagerOptions
This function will load paramters from the ros node handler / paramter server This is the recommended way of loading parameters as compared to the command line version.

Function documentation

VioManagerOptions ov_msckf::parse_command_line_arguments(int argc, char** argv)

This function will parse the command line arugments using CLI11. This is only used if you are not building with ROS, and thus isn't the primary supported way to pass arguments. We recommend building with ROS as compared using this parser.

Parameters
argc Number of parameters
argv Pointer to string passed as options
Returns A fully loaded VioManagerOptions object

VioManagerOptions ov_msckf::parse_ros_nodehandler(ros::NodeHandle& nh)

This function will load paramters from the ros node handler / paramter server This is the recommended way of loading parameters as compared to the command line version.

Parameters
nh ROS node handler
Returns A fully loaded VioManagerOptions object