41 #ifndef INCLUDE_OKVIS_VIOBACKENDINTERFACE_HPP_ 
   42 #define INCLUDE_OKVIS_VIOBACKENDINTERFACE_HPP_ 
   46 #include <ceres/ceres.h> 
   70   EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 
  122                          bool asKeyframe) = 0;
 
  131                            const Eigen::Vector4d & landmark) = 0;
 
  141   virtual bool removeObservation(uint64_t landmarkId, uint64_t poseId,  
size_t camIdx,
 
  142                          size_t keypointIdx) = 0;
 
  149   virtual void optimize(
size_t numIter, 
size_t numThreads = 1, 
bool verbose = 
false) = 0;
 
  239     OKVIS_THROW(Exception,
"Uncertainty computation not implemented");
 
  249   virtual bool isKeyframe(uint64_t frameId) 
const = 0;
 
  266     OKVIS_THROW(Exception,
"Uncertainty computation not implemented");
 
  276     OKVIS_THROW(Exception,
"Uncertainty computation not implemented");
 
  315                            const Eigen::Vector4d & landmark) = 0;
 
  329   virtual void setMap(std::shared_ptr<okvis::ceres::Map> mapPtr) = 0;
 
Struct to define the behavior of the camera extrinsics. 
Definition: Parameters.hpp:60
 
virtual void setLandmarkInitialized(uint64_t landmarkId, bool initialized)=0
Set the landmark initialization state. 
 
A type to store information about a point in the world map. 
Definition: FrameTypedefs.hpp:139
 
virtual bool setOptimizationTimeLimit(double timeLimit, int minIterations)=0
Set a time limit for the optimization process. 
 
std::deque< ImuMeasurement, Eigen::aligned_allocator< ImuMeasurement > > ImuMeasurementDeque
Definition: Measurements.hpp:163
 
virtual bool isKeyframe(uint64_t frameId) const =0
Checks if a particular frame is a keyframe. 
 
virtual int addCamera(const ExtrinsicsEstimationParameters &extrinsicsEstimationParameters)=0
Add a camera to the configuration. Sensors can only be added and never removed. 
 
Header file for the PoseParameterBlock class. 
 
virtual bool getLandmark(uint64_t landmarkId, MapPoint &mapPoint) const =0
Get a specific landmark. 
 
Header file for the MultiFrame class. 
 
Header file for the Map class. This essentially encapsulates the ceres::Problem. 
 
Eigen::Matrix< double, 9, 1 > SpeedAndBias
Definition: FrameTypedefs.hpp:234
 
std::shared_ptr< MultiFrame > MultiFramePtr
For convenience. 
Definition: MultiFrame.hpp:272
 
This file contains the templated measurement structs, structs encapsulating Sensor data and related t...
 
virtual bool getStateUncertainty(Eigen::Matrix< double, 15, 15 > &) const 
Get the current frame state uncertainty. param[out] P_T_WS Current pose uncertainty w...
Definition: VioBackendInterface.hpp:275
 
virtual void setComputeUncertainty(bool)
Request computation of uncertainties. param[in] computeUncertainty True, if uncertainties should be c...
Definition: VioBackendInterface.hpp:333
 
virtual bool isLandmarkInitialized(uint64_t landmarkId) const =0
Checks whether the landmark is initialized. 
 
Header file for the ReprojectionError class. 
 
Header file for the HomogeneousPointParameterBlock class. 
 
#define OKVIS_THROW(exceptionType, message)
Definition: assert_macros.hpp:98
 
#define OKVIS_DEFINE_EXCEPTION(exceptionName, exceptionParent)
Macro for defining an exception with a given parent. 
Definition: assert_macros.hpp:52
 
virtual bool getCameraSensorStates(uint64_t poseId, size_t cameraIdx, okvis::kinematics::Transformation &T_SCi) const =0
Get camera states for a given pose ID. 
 
virtual bool getPoseUncertainty(Eigen::Matrix< double, 6, 6 > &) const 
Get the current frame pose uncertainty. param[out] P_T_WS Current pose uncertainty w...
Definition: VioBackendInterface.hpp:265
 
virtual bool get_T_WS(uint64_t poseId, okvis::kinematics::Transformation &T_WS) const =0
Get pose for a given pose ID. 
 
This file contains some useful assert macros. 
 
Header file for the SpeedAndBiasParameterBlock class. 
 
virtual size_t getLandmarks(PointMap &landmarks) const =0
Get a copy of all the landmarks as a PointMap. 
 
virtual ~VioBackendInterface()
Definition: VioBackendInterface.hpp:74
 
Initialization not started. 
 
virtual void clearCameras()=0
Remove all cameras from the configuration. 
 
This file contains some typedefs related to state variables. 
 
virtual okvis::MultiFramePtr multiFrame(uint64_t frameId) const =0
Get a multiframe. 
 
virtual bool setLandmark(uint64_t landmarkId, const Eigen::Vector4d &landmark)=0
Set the homogeneous coordinates for a landmark. 
 
virtual bool set_T_WS(uint64_t poseId, const okvis::kinematics::Transformation &T_WS)=0
Set pose for a given pose ID. 
 
virtual InitializationStatus initializationStatus() const 
Obtain the initialization status. 
Definition: VioBackendInterface.hpp:238
 
virtual bool isLandmarkAdded(uint64_t landmarkId) const =0
Checks whether the landmark is added to the estimator. 
 
InitializationStatus
Enum to define the status of initialization. 
Definition: VioBackendInterface.hpp:77
 
virtual void clearImus()=0
Remove all IMUs from the configuration. 
 
IMU parameters. 
Definition: Parameters.hpp:105
 
std::map< uint64_t, MapPoint, std::less< uint64_t >, Eigen::aligned_allocator< MapPoint > > PointMap
Definition: FrameTypedefs.hpp:174
 
virtual bool setCameraSensorStates(uint64_t poseId, size_t cameraIdx, const okvis::kinematics::Transformation &T_SCi)=0
Set the transformation from sensor to camera frame for a given pose ID. 
 
virtual size_t numFrames() const =0
Get the number of states/frames in the estimator. 
 
virtual void setKeyframe(uint64_t frameId, bool isKeyframe)=0
Set whether a frame is a keyframe or not. 
 
virtual bool addLandmark(uint64_t landmarkId, const Eigen::Vector4d &landmark)=0
Add a landmark. 
 
Time representation. May either represent wall clock time or ROS clock time. 
Definition: Time.hpp:187
 
virtual void setMap(std::shared_ptr< okvis::ceres::Map > mapPtr)=0
Set ceres map. 
 
This file contains struct definitions that encapsulate parameters and settings. 
 
virtual size_t numLandmarks() const =0
Get the number of landmarks in the backend. 
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW VioBackendInterface()
Default constructor. 
Definition: VioBackendInterface.hpp:73
 
virtual bool getSpeedAndBias(uint64_t poseId, uint64_t imuIdx, okvis::SpeedAndBias &speedAndBias) const =0
Get speeds and IMU biases for a given pose ID. 
 
virtual bool setSpeedAndBias(uint64_t poseId, size_t imuIdx, const okvis::SpeedAndBias &speedAndBias)=0
Set the speeds and IMU biases for a given pose ID. 
 
virtual uint64_t currentFrameId() const =0
Get the ID of the newest frame added to the state. 
 
virtual bool removeObservation(uint64_t landmarkId, uint64_t poseId, size_t camIdx, size_t keypointIdx)=0
Remove an observation from a landmark, if available. 
 
virtual int addImu(const ImuParameters &imuParameters)=0
Add an IMU to the configuration. 
 
virtual okvis::Time timestamp(uint64_t frameId) const =0
Get the timestamp for a particular frame. 
 
virtual void optimize(size_t numIter, size_t numThreads=1, bool verbose=false)=0
Start optimization. 
 
Header file for the MarginalizationError class. 
 
An abstract interface for backends. 
Definition: VioBackendInterface.hpp:67
 
This file contains useful typedefs and structs related to frames. 
 
virtual bool addStates(okvis::MultiFramePtr multiFrame, const okvis::ImuMeasurementDeque &imuMeasurements, bool asKeyframe)=0
Add a pose to the state.