OKVIS ROS
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
MockVioBackendInterface.hpp
Go to the documentation of this file.
1 /*********************************************************************************
2  * OKVIS - Open Keyframe-based Visual-Inertial SLAM
3  * Copyright (c) 2015, Autonomous Systems Lab / ETH Zurich
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright notice,
9  * this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright notice,
11  * this list of conditions and the following disclaimer in the documentation
12  * and/or other materials provided with the distribution.
13  * * Neither the name of Autonomous Systems Lab / ETH Zurich nor the names of
14  * its contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Created on: Aug 21, 2014
30  * Author: Stefan Leutenegger (s.leutenegger@imperial.ac.uk)
31  *********************************************************************************/
32 
33 #ifndef MockVioBackendInterface_HPP_
34 #define MockVioBackendInterface_HPP_
35 
36 #include "gmock/gmock.h"
37 #include "gtest/gtest.h"
38 
40 
42 namespace okvis {
43 
45  public:
47  int(const ExtrinsicsEstimationParameters & extrinsicsEstimationParameters));
49  int(const ImuParameters & imuParameters));
51  void());
53  void());
54 
56  bool(okvis::MultiFramePtr multiFrame, const okvis::ImuMeasurementDeque & imuMeasurements, bool asKeyframe));
57 
59  bool(uint64_t landmarkId, const Eigen::Vector4d & landmark));
60  MOCK_METHOD4(addObservation,
61  ::ceres::ResidualBlockId(uint64_t landmarkId, uint64_t poseId, size_t camIdx, size_t keypointIdx));
63  bool(uint64_t landmarkId, uint64_t poseId, size_t camIdx, size_t keypointIdx));
64  MOCK_METHOD3(applyMarginalizationStrategy,
65  bool(size_t numKeyframes, size_t numImuFrames, okvis::MapPointVector& removedLandmarks));
67  void(size_t, size_t, bool));
69  bool(double timeLimit, int minIterations));
71  bool(uint64_t landmarkId));
73  bool(uint64_t landmarkId));
75  bool(uint64_t landmarkId, MapPoint& mapPoint));
77  size_t(PointMap & landmarks));
79  size_t(okvis::MapPointVector& landmarks));
80  MOCK_CONST_METHOD1(multiFrame,
81  okvis::MultiFramePtr(uint64_t frameId));
83  bool(uint64_t poseId, okvis::kinematics::Transformation & T_WS));
85  bool(uint64_t poseId, uint64_t imuIdx, okvis::SpeedAndBias & speedAndBias));
87  bool(uint64_t poseId, size_t cameraIdx, okvis::kinematics::Transformation & T_SCi));
89  size_t());
91  size_t());
92  MOCK_CONST_METHOD0(currentKeyframeId,
93  uint64_t());
94  MOCK_CONST_METHOD1(frameIdByAge,
95  uint64_t(size_t age));
97  uint64_t());
99  bool(uint64_t frameId));
100  MOCK_CONST_METHOD1(isInImuWindow,
101  bool(uint64_t frameId));
103  okvis::Time(uint64_t frameId));
105  bool(uint64_t poseId, const okvis::kinematics::Transformation & T_WS));
107  bool(uint64_t poseId, size_t imuIdx, const okvis::SpeedAndBias & speedAndBias));
109  bool(uint64_t poseId, size_t cameraIdx, const okvis::kinematics::Transformation & T_SCi));
111  bool(uint64_t landmarkId, const Eigen::Vector4d & landmark));
113  void(uint64_t landmarkId, bool initialized));
115  void(uint64_t frameId, bool isKeyframe));
117  void(std::shared_ptr<okvis::ceres::Map> mapPtr));
120 };
121 
122 } // namespace okvis
123 
124 #endif /* MockVioBackendInterface_HPP_ */
MOCK_METHOD3(addStates, bool(okvis::MultiFramePtr multiFrame, const okvis::ImuMeasurementDeque &imuMeasurements, bool asKeyframe))
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
MOCK_CONST_METHOD0(numFrames, size_t())
MOCK_METHOD0(clearCameras, void())
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.
virtual bool getLandmark(uint64_t landmarkId, MapPoint &mapPoint) const =0
Get a specific landmark.
MOCK_METHOD1(addCamera, int(const ExtrinsicsEstimationParameters &extrinsicsEstimationParameters))
MOCK_METHOD2(addLandmark, bool(uint64_t landmarkId, const Eigen::Vector4d &landmark))
Eigen::Matrix< double, 9, 1 > SpeedAndBias
Definition: FrameTypedefs.hpp:234
MOCK_METHOD4(addObservation,::ceres::ResidualBlockId(uint64_t landmarkId, uint64_t poseId, size_t camIdx, size_t keypointIdx))
Definition: MockVioBackendInterface.hpp:44
std::shared_ptr< MultiFrame > MultiFramePtr
For convenience.
Definition: MultiFrame.hpp:272
A class that does homogeneous transformations. This relates a frame A and B: T_AB; it consists of tra...
Definition: Transformation.hpp:76
virtual bool isLandmarkInitialized(uint64_t landmarkId) const =0
Checks whether the landmark is initialized.
std::vector< MapPoint, Eigen::aligned_allocator< MapPoint > > MapPointVector
Definition: FrameTypedefs.hpp:172
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 get_T_WS(uint64_t poseId, okvis::kinematics::Transformation &T_WS) const =0
Get pose for a given pose ID.
virtual size_t getLandmarks(PointMap &landmarks) const =0
Get a copy of all the landmarks as a PointMap.
virtual void clearCameras()=0
Remove all cameras from the configuration.
MOCK_CONST_METHOD3(getSpeedAndBias, bool(uint64_t poseId, uint64_t imuIdx, okvis::SpeedAndBias &speedAndBias))
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
MOCK_CONST_METHOD1(isLandmarkAdded, bool(uint64_t landmarkId))
virtual void setMap(std::shared_ptr< okvis::ceres::Map > mapPtr)=0
Set ceres map.
virtual size_t numLandmarks() const =0
Get the number of landmarks in the backend.
Header file for the VioBackendInterface class.
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.
An abstract interface for backends.
Definition: VioBackendInterface.hpp:67
MOCK_CONST_METHOD2(getLandmark, bool(uint64_t landmarkId, MapPoint &mapPoint))
virtual bool addStates(okvis::MultiFramePtr multiFrame, const okvis::ImuMeasurementDeque &imuMeasurements, bool asKeyframe)=0
Add a pose to the state.