OKVIS ROS
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
Public Member Functions | List of all members
okvis::VioFrontendInterface Class Referenceabstract

The VioFrontendInterface class is an interface for frontends. More...

#include <VioFrontendInterface.hpp>

Inheritance diagram for okvis::VioFrontendInterface:
okvis::Frontend

Public Member Functions

 VioFrontendInterface ()
 
virtual ~VioFrontendInterface ()
 

In the derived class, the following methods (and nothing else) have to be implemented:

virtual bool detectAndDescribe (size_t cameraIndex, std::shared_ptr< okvis::MultiFrame > frameOut, const okvis::kinematics::Transformation &T_WC, const std::vector< cv::KeyPoint > *keypoints)=0
 Detection and descriptor extraction on a per image basis. More...
 
virtual bool dataAssociationAndInitialization (okvis::Estimator &estimator, okvis::kinematics::Transformation &T_WS_propagated, const okvis::VioParameters &params, const std::shared_ptr< okvis::MapPointVector > map, std::shared_ptr< okvis::MultiFrame > framesInOut, bool *asKeyframe)=0
 Matching as well as initialization of landmarks and state. More...
 
virtual bool propagation (const okvis::ImuMeasurementDeque &imuMeasurements, const okvis::ImuParameters &imuParams, okvis::kinematics::Transformation &T_WS_propagated, okvis::SpeedAndBias &speedAndBiases, const okvis::Time &t_start, const okvis::Time &t_end, Eigen::Matrix< double, 15, 15 > *covariance, Eigen::Matrix< double, 15, 15 > *jacobian) const =0
 Propagates pose, speeds and biases with given IMU measurements. More...
 

Detailed Description

The VioFrontendInterface class is an interface for frontends.

Constructor & Destructor Documentation

okvis::VioFrontendInterface::VioFrontendInterface ( )
inline
virtual okvis::VioFrontendInterface::~VioFrontendInterface ( )
inlinevirtual

Member Function Documentation

virtual bool okvis::VioFrontendInterface::dataAssociationAndInitialization ( okvis::Estimator estimator,
okvis::kinematics::Transformation T_WS_propagated,
const okvis::VioParameters params,
const std::shared_ptr< okvis::MapPointVector map,
std::shared_ptr< okvis::MultiFrame framesInOut,
bool *  asKeyframe 
)
pure virtual

Matching as well as initialization of landmarks and state.

Parameters
estimatorEstimator.
T_WS_propagatedPose of sensor at image capture time.
paramsConfiguration parameters.
mapCurrent map.
framesInOutMultiframe including the descriptors of all the keypoints.
[out]asKeyframeShould the frame be a keyframe?
Returns
True if successful.

Implemented in okvis::Frontend.

virtual bool okvis::VioFrontendInterface::detectAndDescribe ( size_t  cameraIndex,
std::shared_ptr< okvis::MultiFrame frameOut,
const okvis::kinematics::Transformation T_WC,
const std::vector< cv::KeyPoint > *  keypoints 
)
pure virtual

Detection and descriptor extraction on a per image basis.

Parameters
cameraIndexIndex of camera to do detection and description.
frameOutMultiframe containing the frames. Resulting keypoints and descriptors are saved in here.
T_WCPose of camera with index cameraIndex at image capture time.
[in]keypointsIf the keypoints are already available from a different source, provide them here in order to skip detection.
Returns
True if successful.

Implemented in okvis::Frontend.

virtual bool okvis::VioFrontendInterface::propagation ( const okvis::ImuMeasurementDeque imuMeasurements,
const okvis::ImuParameters imuParams,
okvis::kinematics::Transformation T_WS_propagated,
okvis::SpeedAndBias speedAndBiases,
const okvis::Time t_start,
const okvis::Time t_end,
Eigen::Matrix< double, 15, 15 > *  covariance,
Eigen::Matrix< double, 15, 15 > *  jacobian 
) const
pure virtual

Propagates pose, speeds and biases with given IMU measurements.

See Also
okvis::ceres::ImuError::propagation()
Parameters
[in]imuMeasurementsAll the IMU measurements.
[in]imuParamsThe parameters to be used.
[in,out]T_WS_propagatedStart pose.
[in,out]speedAndBiasesStart speed and biases.
[in]t_startStart time.
[in]t_endEnd time.
[out]covarianceCovariance for GIVEN start states.
[out]jacobianJacobian w.r.t. start states.
Returns
True on success.

Implemented in okvis::Frontend.


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