OKVIS
|
This class manages the complete data flow in and out of the algorithm, as well as between the processing threads. More...
#include <ThreadedKFVio.hpp>
Classes | |
struct | OptimizationResults |
This struct contains the results of the optimization for ease of publication. It is also used for publishing poses that have been propagated with the IMU measurements. More... | |
Public Member Functions | |
ThreadedKFVio (okvis::VioParameters ¶meters) | |
Constructor. More... | |
virtual | ~ThreadedKFVio () |
Destructor. This calls Shutdown() for all threadsafe queues and joins all threads. More... | |
void | display () |
Trigger display (needed because OSX won't allow threaded display). 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) |
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) |
Add an abstracted image observation. More... | |
virtual bool | addImuMeasurement (const okvis::Time &stamp, const Eigen::Vector3d &alpha, const Eigen::Vector3d &omega) |
Add an IMU measurement. More... | |
virtual void | addPositionMeasurement (const okvis::Time &stamp, const Eigen::Vector3d &position, const Eigen::Vector3d &positionOffset, const Eigen::Matrix3d &positionCovariance) |
Add a position measurement. More... | |
virtual void | addGpsMeasurement (const okvis::Time &stamp, double lat_wgs84_deg, double lon_wgs84_deg, double alt_wgs84_deg, const Eigen::Vector3d &positionOffset, const Eigen::Matrix3d &positionCovarianceENU) |
Add a GPS measurement. More... | |
virtual void | addMagnetometerMeasurement (const okvis::Time &stamp, const Eigen::Vector3d &fluxDensityMeas, double stdev) |
Add a magnetometer measurement. More... | |
virtual void | addBarometerMeasurement (const okvis::Time &stamp, double staticPressure, double stdev) |
Add a static pressure measurement. More... | |
virtual void | addDifferentialPressureMeasurement (const okvis::Time &stamp, double differentialPressure, double stdev) |
Add a differential pressure measurement. More... | |
Setters | |
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... | |
Public Member Functions inherited from okvis::VioInterface | |
VioInterface () | |
virtual | ~VioInterface () |
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... | |
bool | addEigenImage (const okvis::Time &stamp, size_t cameraIndex, const EigenImage &image) |
This is just handy for the python interface. More... | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef okvis::timing::Timer | TimerSwitchable |
Private Member Functions | |
virtual void | startThreads () |
Start all threads. More... | |
void | init () |
Initialises settings and calls startThreads(). More... | |
void | frameConsumerLoop (size_t cameraIndex) |
Loop to process frames from camera with index cameraIndex. More... | |
void | matchingLoop () |
Loop that matches frames with existing frames. More... | |
void | imuConsumerLoop () |
Loop to process IMU measurements. More... | |
void | positionConsumerLoop () |
Loop to process position measurements. More... | |
void | gpsConsumerLoop () |
Loop to process GPS measurements. More... | |
void | magnetometerConsumerLoop () |
Loop to process magnetometer measurements. More... | |
void | differentialConsumerLoop () |
Loop to process differential pressure measurements. More... | |
void | visualizationLoop () |
Loop that visualizes completed frames. More... | |
void | optimizationLoop () |
Loop that performs the optimization and marginalisation. More... | |
void | publisherLoop () |
Loop that publishes the newest state and landmarks. More... | |
okvis::ImuMeasurementDeque | getImuMeasurments (okvis::Time &start, okvis::Time &end) |
Get a subset of the recorded IMU measurements. More... | |
int | deleteImuMeasurements (const okvis::Time &eraseUntil) |
Remove IMU measurements from the internal buffer. More... | |
Private Attributes | |
ImuFrameSynchronizer | imuFrameSynchronizer_ |
okvis::FrameSynchronizer | frameSynchronizer_ |
The frame synchronizer responsible for merging frames into multiframes. More... | |
okvis::Time | lastAddedStateTimestamp_ |
Timestamp of the newest state in the Estimator. More... | |
okvis::Time | lastAddedImageTimestamp_ |
Timestamp of the newest image added to the image input queue. More... | |
size_t | numCameras_ |
Number of cameras in the system. More... | |
size_t | numCameraPairs_ |
Number of camera pairs in the system. More... | |
okvis::VioParameters | parameters_ |
The parameters and settings. More... | |
const size_t | maxImuInputQueueSize_ |
const size_t | maxPositionInputQueueSize_ = 10 |
Max position measurements before dropping. More... | |
State variables | |
okvis::SpeedAndBias | speedAndBiases_propagated_ |
okvis::ImuParameters | imu_params_ |
The IMU parameters. More... | |
okvis::kinematics::Transformation | T_WS_propagated_ |
The pose propagated by the IMU measurements. More... | |
std::shared_ptr < okvis::MapPointVector > | map_ |
The map. Unused. More... | |
okvis::kinematics::Transformation | lastOptimized_T_WS_ |
Resulting pose of the last optimization. More... | |
okvis::SpeedAndBias | lastOptimizedSpeedAndBiases_ |
Resulting speeds and IMU biases after last optimization. More... | |
okvis::Time | lastOptimizedStateTimestamp_ |
Timestamp of newest frame used in the last optimization. More... | |
std::atomic_bool | repropagationNeeded_ |
Measurement input queues | |
std::vector< std::shared_ptr < okvis::threadsafe::ThreadSafeQueue < std::shared_ptr < okvis::CameraMeasurement > > > > | cameraMeasurementsReceived_ |
Camera measurement input queues. For each camera in the configuration one. More... | |
okvis::threadsafe::ThreadSafeQueue < okvis::ImuMeasurement > | imuMeasurementsReceived_ |
IMU measurement input queue. More... | |
okvis::threadsafe::ThreadSafeQueue < okvis::PositionMeasurement > | positionMeasurementsReceived_ |
Position measurement input queue. More... | |
Measurement operation queues. | |
okvis::threadsafe::ThreadSafeQueue < std::shared_ptr < okvis::MultiFrame > > | keypointMeasurements_ |
The queue containing multiframes with completely detected frames. More... | |
okvis::threadsafe::ThreadSafeQueue < std::shared_ptr < okvis::MultiFrame > > | matchedFrames_ |
The queue containing multiframes with completely matched frames. These are already part of the estimator state. More... | |
okvis::ImuMeasurementDeque | imuMeasurements_ |
The IMU measurements. More... | |
okvis::PositionMeasurementDeque | positionMeasurements_ |
The Position measurements. More... | |
okvis::threadsafe::ThreadSafeQueue < OptimizationResults > | optimizationResults_ |
The queue containing the results of the optimization or IMU propagation ready for publishing. More... | |
okvis::threadsafe::ThreadSafeQueue < VioVisualizer::VisualizationData::Ptr > | visualizationData_ |
The queue containing visualization data that is ready to be displayed. More... | |
okvis::threadsafe::ThreadSafeQueue < std::vector< cv::Mat > > | displayImages_ |
The queue containing the actual display images. More... | |
Mutexes | |
std::mutex | imuMeasurements_mutex_ |
Lock when accessing imuMeasurements_. More... | |
std::mutex | positionMeasurements_mutex_ |
Lock when accessing imuMeasurements_. More... | |
std::mutex | frameSynchronizer_mutex_ |
Lock when accessing the frameSynchronizer_. More... | |
std::mutex | estimator_mutex_ |
Condition variable to signalise that optimization is done. More... | |
std::condition_variable | optimizationNotification_ |
std::atomic_bool | optimizationDone_ |
Boolean flag for whether optimization is done for the last state that has been added to the estimator. More... | |
std::mutex | lastState_mutex_ |
Lock when accessing any of the 'lastOptimized*' variables. More... | |
std::vector< std::thread > | frameConsumerThreads_ |
Threads running the frameConsumerLoop(). One per camera. More... | |
std::vector< std::thread > | keypointConsumerThreads_ |
Threads running matchingLoop(). More... | |
std::vector< std::thread > | matchesConsumerThreads_ |
Unused. More... | |
std::thread | imuConsumerThread_ |
Thread running imuConsumerLoop(). More... | |
std::thread | positionConsumerThread_ |
Thread running positionConsumerLoop(). More... | |
std::thread | gpsConsumerThread_ |
Thread running gpsConsumerLoop(). More... | |
std::thread | magnetometerConsumerThread_ |
Thread running magnetometerConsumerLoop(). More... | |
std::thread | differentialConsumerThread_ |
Thread running differentialConsumerLoop(). More... | |
Algorithm threads | |
std::thread | visualizationThread_ |
Thread running visualizationLoop(). More... | |
std::thread | optimizationThread_ |
Thread running optimizationLoop(). More... | |
std::thread | publisherThread_ |
Thread running publisherLoop(). More... | |
Algorithm objects. | |
okvis::Estimator | estimator_ |
The backend estimator. More... | |
okvis::Frontend | frontend_ |
The frontend. More... | |
Additional Inherited Members | |
Public Types inherited from okvis::VioInterface | |
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 |
Protected Types inherited from okvis::VioInterface | |
typedef std::map< size_t, std::shared_ptr< std::fstream > > | FilePtrMap |
Protected Member Functions inherited from okvis::VioInterface | |
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 inherited from okvis::VioInterface | |
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... | |
This class manages the complete data flow in and out of the algorithm, as well as between the processing threads.
To ensure fast return from user callbacks, new data are collected in thread save input queues and are processed in data consumer threads, one for each data source. The algorithm tasks are running in individual threads with thread save queue for message passing. For sending back data to the user, publisher threads are created for each output which ensure that the algorithm is not being blocked by slow users.
All the queues can be limited to size 1 to back propagate processing congestions to the user callback.
okvis::ThreadedKFVio::ThreadedKFVio | ( | okvis::VioParameters & | parameters | ) |
Constructor.
parameters | Parameters and settings. |
|
virtual |
Destructor. This calls Shutdown() for all threadsafe queues and joins all threads.
|
virtual |
Add a static pressure measurement.
stamp | The measurement timestamp. |
staticPressure | Measured static pressure [Pa]. |
stdev | Measurement std deviation [Pa]. |
Reimplemented from okvis::VioInterface.
|
virtual |
Add a differential pressure measurement.
stamp | The measurement timestamp. |
differentialPressure | Measured differential pressure [Pa]. |
stdev | Measurement std deviation [Pa]. |
Reimplemented from okvis::VioInterface.
|
virtual |
Add a GPS measurement.
stamp | The measurement timestamp. |
lat_wgs84_deg | WGS84 latitude [deg]. |
lon_wgs84_deg | WGS84 longitude [deg]. |
alt_wgs84_deg | WGS84 altitude [m]. |
positionOffset | Body frame antenna position offset [m]. |
positionCovarianceENU | The position measurement covariance matrix. |
Reimplemented from okvis::VioInterface.
|
virtual |
Add a new image.
stamp | The image timestamp. |
cameraIndex | The index of the camera that the image originates from. |
image | The image. |
keypoints | Optionally aready pass keypoints. This will skip the detection part. |
asKeyframe | Use the new image as keyframe. Not implemented. |
Implements okvis::VioInterface.
|
virtual |
Add an IMU measurement.
stamp | The measurement timestamp. |
alpha | The acceleration measured at this time. |
omega | The angular velocity measured at this time. |
Implements okvis::VioInterface.
|
virtual |
Add an abstracted image observation.
stamp | The timestamp for the start of integration time for the image. |
cameraIndex | The index of the camera. |
keypoints | A vector where each entry represents a [u,v] keypoint measurement. Also set the size field. |
landmarkIds | A vector of landmark ids for each keypoint measurement. |
descriptors | A matrix containing the descriptors for each keypoint. |
asKeyframe | Optionally force keyframe or not. |
Implements okvis::VioInterface.
|
virtual |
Add a magnetometer measurement.
stamp | The measurement timestamp. |
fluxDensityMeas | Measured magnetic flux density (sensor frame) [uT]. |
stdev | Measurement std deviation [uT]. |
Reimplemented from okvis::VioInterface.
|
virtual |
Add a position measurement.
stamp | The measurement timestamp. |
position | The position in world frame. |
positionOffset | Body frame antenna position offset [m]. |
positionCovariance | The position measurement covariance matrix. |
Reimplemented from okvis::VioInterface.
|
private |
Remove IMU measurements from the internal buffer.
eraseUntil | Remove all measurements that are strictly older than this time. |
|
private |
Loop to process differential pressure measurements.
void okvis::ThreadedKFVio::display | ( | ) |
Trigger display (needed because OSX won't allow threaded display).
|
private |
Loop to process frames from camera with index cameraIndex.
|
private |
Get a subset of the recorded IMU measurements.
start | The first IMU measurement in the return value will be older than this timestamp. |
end | The last IMU measurement in the return value will be newer than this timestamp. |
|
private |
Loop to process GPS measurements.
|
private |
Loop to process IMU measurements.
|
private |
Initialises settings and calls startThreads().
|
private |
Loop to process magnetometer measurements.
|
private |
Loop that matches frames with existing frames.
|
private |
Loop that performs the optimization and marginalisation.
|
private |
Loop to process position measurements.
|
private |
Loop that publishes the newest state and landmarks.
|
virtual |
Set the blocking variable that indicates whether the addMeasurement() functions should return immediately (blocking=false), or only when the processing is complete.
Reimplemented from okvis::VioInterface.
|
privatevirtual |
Start all threads.
|
private |
Loop that visualizes completed frames.
|
private |
Camera measurement input queues. For each camera in the configuration one.
|
private |
Thread running differentialConsumerLoop().
|
private |
The queue containing the actual display images.
|
private |
The backend estimator.
|
private |
Condition variable to signalise that optimization is done.
Lock when accessing the estimator_.
|
private |
Threads running the frameConsumerLoop(). One per camera.
|
private |
The frame synchronizer responsible for merging frames into multiframes.
|
private |
Lock when accessing the frameSynchronizer_.
|
private |
The frontend.
|
private |
Thread running gpsConsumerLoop().
|
private |
The IMU parameters.
|
private |
Thread running imuConsumerLoop().
|
private |
The IMU frame synchronizer.
|
private |
The IMU measurements.
|
private |
Lock when accessing imuMeasurements_.
|
private |
IMU measurement input queue.
|
private |
Threads running matchingLoop().
|
private |
The queue containing multiframes with completely detected frames.
|
private |
Timestamp of the newest image added to the image input queue.
|
private |
Timestamp of the newest state in the Estimator.
|
private |
Resulting pose of the last optimization.
|
private |
Resulting speeds and IMU biases after last optimization.
|
private |
Timestamp of newest frame used in the last optimization.
|
private |
Lock when accessing any of the 'lastOptimized*' variables.
|
private |
Thread running magnetometerConsumerLoop().
|
private |
The map. Unused.
|
private |
The queue containing multiframes with completely matched frames. These are already part of the estimator state.
|
private |
Unused.
|
private |
The maximum input queue size before IMU measurements are dropped. The maximum input queue size for the camera measurements is proportionally higher depending on the ratio between IMU and camera rate.
|
private |
Max position measurements before dropping.
|
private |
Number of camera pairs in the system.
|
private |
Number of cameras in the system.
|
private |
Boolean flag for whether optimization is done for the last state that has been added to the estimator.
|
private |
|
private |
The queue containing the results of the optimization or IMU propagation ready for publishing.
|
private |
Thread running optimizationLoop().
|
private |
The parameters and settings.
|
private |
Thread running positionConsumerLoop().
|
private |
The Position measurements.
|
private |
Lock when accessing imuMeasurements_.
|
private |
Position measurement input queue.
|
private |
Thread running publisherLoop().
|
private |
This is set to true after optimization to signal the IMU consumer loop to repropagate the state from the lastOptimizedStateTimestamp_.
|
private |
The speeds and IMU biases propagated by the IMU measurements.
|
private |
The pose propagated by the IMU measurements.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef okvis::timing::Timer okvis::ThreadedKFVio::TimerSwitchable |
|
private |
The queue containing visualization data that is ready to be displayed.
|
private |
Thread running visualizationLoop().