Static Public Member Functions | List of all members
ov_init::InitializerHelper Class Reference

Has a bunch of helper functions for dynamic initialization (should all be static) More...

#include <helper.h>

Static Public Member Functions

static Eigen::Matrix< double, 7, 1 > compute_dongsi_coeff (Eigen::MatrixXd &D, const Eigen::MatrixXd &d, double gravity_mag)
 Compute coefficients for the constrained optimization quadratic problem. More...
 
static void gram_schmidt (const Eigen::Vector3d &gravity_inI, Eigen::Matrix3d &R_GtoI)
 Given a gravity vector, compute the rotation from the inertial reference frame to this vector. More...
 
static ov_core::ImuData interpolate_data (const ov_core::ImuData &imu_1, const ov_core::ImuData &imu_2, double timestamp)
 Nice helper function that will linearly interpolate between two imu messages. More...
 
static std::vector< ov_core::ImuDataselect_imu_readings (const std::vector< ov_core::ImuData > &imu_data_tmp, double time0, double time1)
 Helper function that given current imu data, will select imu readings between the two times. More...
 

Detailed Description

Has a bunch of helper functions for dynamic initialization (should all be static)

Definition at line 33 of file helper.h.

Member Function Documentation

◆ compute_dongsi_coeff()

static Eigen::Matrix<double, 7, 1> ov_init::InitializerHelper::compute_dongsi_coeff ( Eigen::MatrixXd &  D,
const Eigen::MatrixXd &  d,
double  gravity_mag 
)
inlinestatic

Compute coefficients for the constrained optimization quadratic problem.

https://gist.github.com/goldbattle/3791cbb11bbf4f5feb3f049dad72bfdd

Parameters
DGravity in our sensor frame
dRotation from the arbitrary inertial reference frame to this gravity vector
gravity_magScalar size of gravity (normally is 9.81)
Returns
Coefficents from highest to the constant

Definition at line 183 of file helper.h.

◆ gram_schmidt()

static void ov_init::InitializerHelper::gram_schmidt ( const Eigen::Vector3d &  gravity_inI,
Eigen::Matrix3d &  R_GtoI 
)
inlinestatic

Given a gravity vector, compute the rotation from the inertial reference frame to this vector.

The key assumption here is that our gravity is along the vertical direction in the inertial frame. We can take this vector (z_in_G=0,0,1) and find two arbitrary tangent directions to it. https://en.wikipedia.org/wiki/Gram%E2%80%93Schmidt_process

Parameters
gravity_inIGravity in our sensor frame
R_GtoIRotation from the arbitrary inertial reference frame to this gravity vector

Definition at line 138 of file helper.h.

◆ interpolate_data()

static ov_core::ImuData ov_init::InitializerHelper::interpolate_data ( const ov_core::ImuData imu_1,
const ov_core::ImuData imu_2,
double  timestamp 
)
inlinestatic

Nice helper function that will linearly interpolate between two imu messages.

This should be used instead of just "cutting" imu messages that bound the camera times Give better time offset if we use this function, could try other orders/splines if the imu is slow.

Parameters
imu_1imu at begining of interpolation interval
imu_2imu at end of interpolation interval
timestampTimestamp being interpolated to

Definition at line 45 of file helper.h.

◆ select_imu_readings()

static std::vector<ov_core::ImuData> ov_init::InitializerHelper::select_imu_readings ( const std::vector< ov_core::ImuData > &  imu_data_tmp,
double  time0,
double  time1 
)
inlinestatic

Helper function that given current imu data, will select imu readings between the two times.

This will create measurements that we will integrate with, and an extra measurement at the end. We use the interpolate_data() function to "cut" the imu readings at the beginning and end of the integration. The timestamps passed should already take into account the time offset values.

Parameters
imu_data_tmpIMU data we will select measurements from
time0Start timestamp
time1End timestamp
Returns
Vector of measurements (if we could compute them)

Definition at line 66 of file helper.h.


The documentation for this class was generated from the following file:


ov_init
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Dec 16 2024 03:06:51