ekf_cal  0.4.0
A Kalman filter-based sensor calibration package
MsckfUpdater Class Reference

EKF Updater Class for MSCKF Camera Measurements. More...

#include <msckf_updater.hpp>

Inheritance diagram for MsckfUpdater:
[legend]
Collaboration diagram for MsckfUpdater:
[legend]

Public Member Functions

 MsckfUpdater (unsigned int cam_id, bool is_extrinsic, const std::string &log_file_directory, double data_log_rate, double min_feat_dist, std::shared_ptr< DebugLogger > logger)
 MSCKF EKF Updater constructor. More...
 
bool TriangulateFeature (const double local_time, EKF &ekf, const FeatureTrack &feature_track, Eigen::Vector3d &pos_f_in_l)
 Triangulate feature seen from multiple camera frames. More...
 
void UpdateEKF (EKF &ekf, const double time, const FeatureTracks &feature_tracks, double px_error)
 EKF updater function. More...
 
- Public Member Functions inherited from Updater
 Updater (unsigned int sensor_id, std::shared_ptr< DebugLogger > logger)
 EKF Updater constructor. More...
 

Static Public Member Functions

static void DistortionJacobian (const Eigen::Vector2d &xy_norm, const Intrinsics &intrinsics, Eigen::MatrixXd &H_d)
 Computes the derivative of raw distorted to normalized coordinate. More...
 
static void ProjectionJacobian (const Eigen::Vector3d &position, Eigen::MatrixXd &jacobian)
 Function to calculate jacobian for camera projection function. More...
 
static Eigen::Vector2d Project (const Eigen::Vector3d pos_f_in_c)
 Project a 3D position in the camera frame to a 2D bearing. More...
 
static Eigen::Vector2d Distort (const Eigen::Vector2d &xy_norm, const Intrinsics &intrinsics)
 Distort a normalized camera coordinate using intrinsics. More...
 
- Static Public Member Functions inherited from Updater
static void KalmanUpdate (EKF &ekf, const Eigen::MatrixXd &jacobian, const Eigen::VectorXd &residual, const Eigen::MatrixXd &measurement_noise_input)
 

Additional Inherited Members

- Protected Attributes inherited from Updater
unsigned int m_id
 Associated sensor ID.
 
std::shared_ptr< DebugLoggerm_logger
 Debug logger.
 

Detailed Description

EKF Updater Class for MSCKF Camera Measurements.

Constructor & Destructor Documentation

◆ MsckfUpdater()

MsckfUpdater::MsckfUpdater ( unsigned int  cam_id,
bool  is_extrinsic,
const std::string &  log_file_directory,
double  data_log_rate,
double  min_feat_dist,
std::shared_ptr< DebugLogger logger 
)
explicit

MSCKF EKF Updater constructor.

Parameters
cam_idCamera sensor ID
is_extrinsicCamera extrinsic calibration flag
log_file_directoryDirectory to save log files
data_log_rateMaximum average rate to log data
min_feat_distClosest feature distance to consider
loggerDebug logger pointer

Member Function Documentation

◆ Distort()

Eigen::Vector2d MsckfUpdater::Distort ( const Eigen::Vector2d &  xy_norm,
const Intrinsics intrinsics 
)
static

Distort a normalized camera coordinate using intrinsics.

Parameters
xy_normNormalized camera coordinate
intrinsicscamera intrinsics
Returns
Distorted XY coordinate

◆ DistortionJacobian()

void MsckfUpdater::DistortionJacobian ( const Eigen::Vector2d &  xy_norm,
const Intrinsics intrinsics,
Eigen::MatrixXd &  H_d 
)
static

Computes the derivative of raw distorted to normalized coordinate.

Parameters
xy_normNormalized coordinates we wish to distort
intrinsicsCamera intrinsics
H_dDerivative of measurement z in respect to normalized

◆ Project()

Eigen::Vector2d MsckfUpdater::Project ( const Eigen::Vector3d  pos_f_in_c)
static

Project a 3D position in the camera frame to a 2D bearing.

Parameters
pos_f_in_cFeature position in the camera frame
Returns
Projected 2D position

◆ ProjectionJacobian()

void MsckfUpdater::ProjectionJacobian ( const Eigen::Vector3d &  position,
Eigen::MatrixXd &  jacobian 
)
static

Function to calculate jacobian for camera projection function.

Parameters
positionPosition in camera coordinates
jacobianResulting camera projection jacobian

◆ TriangulateFeature()

bool MsckfUpdater::TriangulateFeature ( const double  local_time,
EKF ekf,
const FeatureTrack feature_track,
Eigen::Vector3d &  pos_f_in_l 
)

Triangulate feature seen from multiple camera frames.

Parameters
ekfEKF address
local_timeMeasurement in EKF time
feature_trackSingle feature track
pos_f_in_lOutput estimate of feature position in camera frame given observations
Returns
If triangulation was successful
Todo:
: Need to continue debugging the triangulated features
Todo:
: Add input flag

◆ UpdateEKF()

void MsckfUpdater::UpdateEKF ( EKF ekf,
const double  time,
const FeatureTracks &  feature_tracks,
double  px_error 
)

EKF updater function.

Parameters
ekfEKF address
timeTime of update
feature_tracksFeature tracks to be used for state update
px_errorStandard deviation of pixel error
Todo:
: Add threshold for total distance/angle before triangulating
Todo:
Chi^2 distance check

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