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

An abstract base class for interfaces between Front- and Backend. More...

#include <VioInterface.hpp>

Inheritance diagram for okvis::VioInterface:
okvis::ThreadedKFVio

Public Types

typedef std::function< void(const
okvis::Time &, const
okvis::kinematics::Transformation &)> 
StateCallback
 
typedef std::function< void(const
okvis::Time &, const
okvis::kinematics::Transformation
&, const Eigen::Matrix< double, 9, 1 >
&, const Eigen::Matrix
< double, 3, 1 > &)> 
FullStateCallback
 
typedef std::function< void(const
okvis::Time &, const
okvis::kinematics::Transformation
&, const Eigen::Matrix< double, 9, 1 >
&, const Eigen::Matrix
< double, 3, 1 > &, const
std::vector
< okvis::kinematics::Transformation,
Eigen::aligned_allocator
< okvis::kinematics::Transformation > > &)> 
FullStateCallbackWithExtrinsics
 
typedef Eigen::Matrix
< unsigned char,
Eigen::Dynamic, Eigen::Dynamic > 
EigenImage
 
typedef std::function< void(const
okvis::Time &, const
okvis::MapPointVector &, const
okvis::MapPointVector &)> 
LandmarksCallback
 

Public Member Functions

 VioInterface ()
 
virtual ~VioInterface ()
 
Setters
bool setImuCsvFile (std::fstream &csvFile)
 Set a CVS file where the IMU data will be saved to. More...
 
bool setImuCsvFile (const std::string &csvFileName)
 Set a CVS file where the IMU data will be saved to. More...
 
bool setTracksCsvFile (size_t cameraId, std::fstream &csvFile)
 Set a CVS file where the tracks (data associations) will be saved to. More...
 
bool setTracksCsvFile (size_t cameraId, const std::string &csvFileName)
 Set a CVS file where the tracks (data associations) will be saved to. More...
 
bool setPosCsvFile (std::fstream &csvFile)
 Set a CVS file where the position measurements will be saved to. More...
 
bool setPosCsvFile (const std::string &csvFileName)
 Set a CVS file where the position measurements will be saved to. More...
 
bool setMagCsvFile (std::fstream &csvFile)
 Set a CVS file where the magnetometer measurements will be saved to. More...
 
bool setMagCsvFile (const std::string &csvFileName)
 Set a CVS file where the magnetometer measurements will be saved to. More...
 
virtual void setStateCallback (const StateCallback &stateCallback)
 Set the stateCallback to be called every time a new state is estimated. When an implementing class has an estimate, they can call: stateCallback_( stamp, T_w_vk ); where stamp is the timestamp and T_w_vk is the transformation (and uncertainty) that transforms points from the vehicle frame to the world frame. More...
 
virtual void setFullStateCallback (const FullStateCallback &fullStateCallback)
 Set the fullStateCallback to be called every time a new state is estimated. When an implementing class has an estimate, they can call: _fullStateCallback( stamp, T_w_vk, speedAndBiases, omega_S); where stamp is the timestamp and T_w_vk is the transformation (and uncertainty) that transforms points from the vehicle frame to the world frame. speedAndBiases contain speed in world frame followed by gyro and acc biases. finally, omega_S is the rotation speed. More...
 
virtual void setFullStateCallbackWithExtrinsics (const FullStateCallbackWithExtrinsics &fullStateCallbackWithExtrinsics)
 Set the fullStateCallbackWithExtrinsics to be called every time a new state is estimated. When an implementing class has an estimate, they can call: _fullStateCallbackWithEctrinsics( stamp, T_w_vk, speedAndBiases, omega_S, vector_of_T_SCi); where stamp is the timestamp and T_w_vk is the transformation (and uncertainty) that transforms points from the vehicle frame to the world frame. speedAndBiases contain speed in world frame followed by gyro and acc biases. omega_S is the rotation speed vector_of_T_SCi contains the (uncertain) transformations of extrinsics T_SCi. More...
 
virtual void setLandmarksCallback (const LandmarksCallback &landmarksCallback)
 Set the landmarksCallback to be called every time a new state is estimated. When an implementing class has an estimate, they can call: landmarksCallback_( stamp, landmarksVector ); where stamp is the timestamp landmarksVector contains all 3D-landmarks with id. More...
 
virtual void setBlocking (bool blocking)
 Set the blocking variable that indicates whether the addMeasurement() functions should return immediately (blocking=false), or only when the processing is complete. More...
 
Add measurements to the algorithm
virtual bool addImage (const okvis::Time &stamp, size_t cameraIndex, const cv::Mat &image, const std::vector< cv::KeyPoint > *keypoints=0, bool *asKeyframe=0)=0
 Add a new image. More...
 
virtual bool addKeypoints (const okvis::Time &stamp, size_t cameraIndex, const std::vector< cv::KeyPoint > &keypoints, const std::vector< uint64_t > &landmarkIds, const cv::Mat &descriptors=cv::Mat(), bool *asKeyframe=0)=0
 Add an abstracted image observation. More...
 
virtual bool addImuMeasurement (const okvis::Time &stamp, const Eigen::Vector3d &alpha, const Eigen::Vector3d &omega)=0
 Add an IMU measurement. More...
 
virtual void addPositionMeasurement (const okvis::Time &, const Eigen::Vector3d &, const Eigen::Vector3d &, const Eigen::Matrix3d &)
 Add a position measurement. More...
 
virtual void addGpsMeasurement (const okvis::Time &, double, double, double, const Eigen::Vector3d &, const Eigen::Matrix3d &)
 Add a position measurement. More...
 
virtual void addMagnetometerMeasurement (const okvis::Time &, const Eigen::Vector3d &, double)
 Add a magnetometer measurement. More...
 
virtual void addBarometerMeasurement (const okvis::Time &, double, double)
 Add a static pressure measurement. More...
 
virtual void addDifferentialPressureMeasurement (const okvis::Time &, double, double)
 Add a differential pressure measurement. More...
 
bool addEigenImage (const okvis::Time &stamp, size_t cameraIndex, const EigenImage &image)
 This is just handy for the python interface. More...
 

Protected Types

typedef std::map< size_t,
std::shared_ptr< std::fstream > > 
FilePtrMap
 

Protected Member Functions

bool writeImuCsvDescription ()
 Write first line of IMU CSV file to describe columns. More...
 
bool writePosCsvDescription ()
 Write first line of position CSV file to describe columns. More...
 
bool writeMagCsvDescription ()
 Write first line of magnetometer CSV file to describe columns. More...
 
bool writeTracksCsvDescription (size_t cameraId)
 Write first line of tracks (data associations) CSV file to describe columns. More...
 

Protected Attributes

StateCallback stateCallback_
 State callback function. More...
 
FullStateCallback fullStateCallback_
 Full state callback function. More...
 
FullStateCallbackWithExtrinsics fullStateCallbackWithExtrinsics_
 Full state and extrinsics callback function. More...
 
LandmarksCallback landmarksCallback_
 Landmarks callback function. More...
 
std::shared_ptr< std::fstream > csvImuFile_
 IMU CSV file. More...
 
std::shared_ptr< std::fstream > csvPosFile_
 Position CSV File. More...
 
std::shared_ptr< std::fstream > csvMagFile_
 Magnetometer CSV File. More...
 
FilePtrMap csvTracksFiles_
 Tracks CSV Files. More...
 
bool blocking_
 Blocking option. Whether the addMeasurement() functions should wait until proccessing is complete. More...
 

Detailed Description

An abstract base class for interfaces between Front- and Backend.

Member Typedef Documentation

typedef Eigen::Matrix<unsigned char, Eigen::Dynamic, Eigen::Dynamic> okvis::VioInterface::EigenImage
typedef std::map<size_t, std::shared_ptr<std::fstream> > okvis::VioInterface::FilePtrMap
protected
typedef std::function< void(const okvis::Time &, const okvis::kinematics::Transformation &, const Eigen::Matrix<double, 9, 1> &, const Eigen::Matrix<double, 3, 1> &)> okvis::VioInterface::FullStateCallback
typedef std::function< void( const okvis::Time &, const okvis::kinematics::Transformation &, const Eigen::Matrix<double, 9, 1> &, const Eigen::Matrix<double, 3, 1> &, const std::vector<okvis::kinematics::Transformation, Eigen::aligned_allocator<okvis::kinematics::Transformation> >&)> okvis::VioInterface::FullStateCallbackWithExtrinsics
typedef std::function< void(const okvis::Time &, const okvis::MapPointVector &, const okvis::MapPointVector &)> okvis::VioInterface::LandmarksCallback

Constructor & Destructor Documentation

okvis::VioInterface::VioInterface ( )
okvis::VioInterface::~VioInterface ( )
virtual

Member Function Documentation

virtual void okvis::VioInterface::addBarometerMeasurement ( const okvis::Time ,
double  ,
double   
)
inlinevirtual

Add a static pressure measurement.

Warning
Not Implemented.

Reimplemented in okvis::ThreadedKFVio.

virtual void okvis::VioInterface::addDifferentialPressureMeasurement ( const okvis::Time ,
double  ,
double   
)
inlinevirtual

Add a differential pressure measurement.

Warning
Not Implemented.

Reimplemented in okvis::ThreadedKFVio.

bool okvis::VioInterface::addEigenImage ( const okvis::Time stamp,
size_t  cameraIndex,
const EigenImage image 
)

This is just handy for the python interface.

Parameters
stampThe image timestamp
cameraIndexThe index of the camera that the image originates from.
imageThe image.
Returns
Returns true normally. False, if the previous one has not been processed yet.
virtual void okvis::VioInterface::addGpsMeasurement ( const okvis::Time ,
double  ,
double  ,
double  ,
const Eigen::Vector3d &  ,
const Eigen::Matrix3d &   
)
inlinevirtual

Add a position measurement.

Warning
Not Implemented.

Reimplemented in okvis::ThreadedKFVio.

virtual bool okvis::VioInterface::addImage ( const okvis::Time stamp,
size_t  cameraIndex,
const cv::Mat &  image,
const std::vector< cv::KeyPoint > *  keypoints = 0,
bool *  asKeyframe = 0 
)
pure virtual

Add a new image.

Parameters
stampThe image timestamp.
cameraIndexThe index of the camera that the image originates from.
imageThe image.
keypointsOptionally aready pass keypoints. This will skip the detection part.
asKeyframeUse the new image as keyframe. Not implemented.
Warning
The frame consumer loop does not support using existing keypoints yet.
Already specifying whether this frame should be a keyframe is not implemented yet.
Returns
Returns true normally. False, if the previous one has not been processed yet.

Implemented in okvis::ThreadedKFVio.

virtual bool okvis::VioInterface::addImuMeasurement ( const okvis::Time stamp,
const Eigen::Vector3d &  alpha,
const Eigen::Vector3d &  omega 
)
pure virtual

Add an IMU measurement.

Parameters
stampThe measurement timestamp.
alphaThe acceleration measured at this time.
omegaThe angular velocity measured at this time.

Implemented in okvis::ThreadedKFVio.

virtual bool okvis::VioInterface::addKeypoints ( const okvis::Time stamp,
size_t  cameraIndex,
const std::vector< cv::KeyPoint > &  keypoints,
const std::vector< uint64_t > &  landmarkIds,
const cv::Mat &  descriptors = cv::Mat(),
bool *  asKeyframe = 0 
)
pure virtual

Add an abstracted image observation.

Parameters
stampThe timestamp for the start of integration time for the image.
cameraIndexThe index of the camera.
keypointsA vector where each entry represents a [u,v] keypoint measurement. Also set the size field.
landmarkIdsA vector of landmark ids for each keypoint measurement.
descriptorsA matrix containing the descriptors for each keypoint.
asKeyframeOptionally force keyframe or not.
Returns
Returns true normally. False, if the previous one has not been processed yet.

Implemented in okvis::ThreadedKFVio.

virtual void okvis::VioInterface::addMagnetometerMeasurement ( const okvis::Time ,
const Eigen::Vector3d &  ,
double   
)
inlinevirtual

Add a magnetometer measurement.

Warning
Not Implemented.
Returns
Returns true normally. False, if the previous one has not been processed yet.

Reimplemented in okvis::ThreadedKFVio.

virtual void okvis::VioInterface::addPositionMeasurement ( const okvis::Time ,
const Eigen::Vector3d &  ,
const Eigen::Vector3d &  ,
const Eigen::Matrix3d &   
)
inlinevirtual

Add a position measurement.

Warning
Not Implemented.

Reimplemented in okvis::ThreadedKFVio.

void okvis::VioInterface::setBlocking ( bool  blocking)
virtual

Set the blocking variable that indicates whether the addMeasurement() functions should return immediately (blocking=false), or only when the processing is complete.

Reimplemented in okvis::ThreadedKFVio.

void okvis::VioInterface::setFullStateCallback ( const FullStateCallback fullStateCallback)
virtual

Set the fullStateCallback to be called every time a new state is estimated. When an implementing class has an estimate, they can call: _fullStateCallback( stamp, T_w_vk, speedAndBiases, omega_S); where stamp is the timestamp and T_w_vk is the transformation (and uncertainty) that transforms points from the vehicle frame to the world frame. speedAndBiases contain speed in world frame followed by gyro and acc biases. finally, omega_S is the rotation speed.

void okvis::VioInterface::setFullStateCallbackWithExtrinsics ( const FullStateCallbackWithExtrinsics fullStateCallbackWithExtrinsics)
virtual

Set the fullStateCallbackWithExtrinsics to be called every time a new state is estimated. When an implementing class has an estimate, they can call: _fullStateCallbackWithEctrinsics( stamp, T_w_vk, speedAndBiases, omega_S, vector_of_T_SCi); where stamp is the timestamp and T_w_vk is the transformation (and uncertainty) that transforms points from the vehicle frame to the world frame. speedAndBiases contain speed in world frame followed by gyro and acc biases. omega_S is the rotation speed vector_of_T_SCi contains the (uncertain) transformations of extrinsics T_SCi.

bool okvis::VioInterface::setImuCsvFile ( std::fstream &  csvFile)

Set a CVS file where the IMU data will be saved to.

Parameters
csvFileThe file.
bool okvis::VioInterface::setImuCsvFile ( const std::string &  csvFileName)

Set a CVS file where the IMU data will be saved to.

Parameters
csvFileNameThe filename of a new file.
void okvis::VioInterface::setLandmarksCallback ( const LandmarksCallback landmarksCallback)
virtual

Set the landmarksCallback to be called every time a new state is estimated. When an implementing class has an estimate, they can call: landmarksCallback_( stamp, landmarksVector ); where stamp is the timestamp landmarksVector contains all 3D-landmarks with id.

bool okvis::VioInterface::setMagCsvFile ( std::fstream &  csvFile)

Set a CVS file where the magnetometer measurements will be saved to.

Parameters
csvFileThe file.
bool okvis::VioInterface::setMagCsvFile ( const std::string &  csvFileName)

Set a CVS file where the magnetometer measurements will be saved to.

Parameters
csvFileNameThe filename of a new file.
bool okvis::VioInterface::setPosCsvFile ( std::fstream &  csvFile)

Set a CVS file where the position measurements will be saved to.

Parameters
csvFileThe file.
bool okvis::VioInterface::setPosCsvFile ( const std::string &  csvFileName)

Set a CVS file where the position measurements will be saved to.

Parameters
csvFileNameThe filename of a new file.
void okvis::VioInterface::setStateCallback ( const StateCallback stateCallback)
virtual

Set the stateCallback to be called every time a new state is estimated. When an implementing class has an estimate, they can call: stateCallback_( stamp, T_w_vk ); where stamp is the timestamp and T_w_vk is the transformation (and uncertainty) that transforms points from the vehicle frame to the world frame.

bool okvis::VioInterface::setTracksCsvFile ( size_t  cameraId,
std::fstream &  csvFile 
)

Set a CVS file where the tracks (data associations) will be saved to.

Parameters
cameraIdThe camera ID.
csvFileThe file.
bool okvis::VioInterface::setTracksCsvFile ( size_t  cameraId,
const std::string &  csvFileName 
)

Set a CVS file where the tracks (data associations) will be saved to.

Parameters
cameraIdThe camera ID.
csvFileNameThe filename of a new file.
bool okvis::VioInterface::writeImuCsvDescription ( )
protected

Write first line of IMU CSV file to describe columns.

bool okvis::VioInterface::writeMagCsvDescription ( )
protected

Write first line of magnetometer CSV file to describe columns.

bool okvis::VioInterface::writePosCsvDescription ( )
protected

Write first line of position CSV file to describe columns.

bool okvis::VioInterface::writeTracksCsvDescription ( size_t  cameraId)
protected

Write first line of tracks (data associations) CSV file to describe columns.

Member Data Documentation

bool okvis::VioInterface::blocking_
protected

Blocking option. Whether the addMeasurement() functions should wait until proccessing is complete.

std::shared_ptr<std::fstream> okvis::VioInterface::csvImuFile_
protected

IMU CSV file.

std::shared_ptr<std::fstream> okvis::VioInterface::csvMagFile_
protected

Magnetometer CSV File.

std::shared_ptr<std::fstream> okvis::VioInterface::csvPosFile_
protected

Position CSV File.

FilePtrMap okvis::VioInterface::csvTracksFiles_
protected

Tracks CSV Files.

FullStateCallback okvis::VioInterface::fullStateCallback_
protected

Full state callback function.

FullStateCallbackWithExtrinsics okvis::VioInterface::fullStateCallbackWithExtrinsics_
protected

Full state and extrinsics callback function.

LandmarksCallback okvis::VioInterface::landmarksCallback_
protected

Landmarks callback function.

StateCallback okvis::VioInterface::stateCallback_
protected

State callback function.


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