OKVIS
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
MockVioFrontendInterface.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 MOCK_FRONTEND_HPP_
34 #define MOCK_FRONTEND_HPP_
35 
36 #define GTEST_USE_OWN_TR1_TUPLE 0
37 #include "gmock/gmock.h"
38 #include "gtest/gtest.h"
39 
41 namespace okvis {
42 
44  public:
45  MOCK_METHOD4(detectAndDescribe,
46  bool(size_t cameraIndex, std::shared_ptr<okvis::MultiFrame> frameOut, const okvis::kinematics::Transformation& T_WC, const std::vector<cv::KeyPoint> * keypoints));
47  MOCK_METHOD6(dataAssociationAndInitialization,
48  bool(okvis::VioBackendInterface& 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));
49  MOCK_CONST_METHOD8(propagation,
50  bool(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));
51  MOCK_METHOD1(setBriskDetectionOctaves,
52  void(size_t octaves));
53  MOCK_METHOD1(setBriskDetectionThreshold,
54  void(double threshold));
55 };
56 
57 } // namespace okvis
58 
59 
60 #endif /* MOCK_DUMMYVIO_HPP_ */
Definition: MockVioFrontendInterface.hpp:43
std::deque< ImuMeasurement, Eigen::aligned_allocator< ImuMeasurement > > ImuMeasurementDeque
Definition: Measurements.hpp:163
Eigen::Matrix< double, 9, 1 > SpeedAndBias
Definition: FrameTypedefs.hpp:234
MOCK_METHOD6(dataAssociationAndInitialization, bool(okvis::VioBackendInterface &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))
A class that does homogeneous transformations. This relates a frame A and B: T_AB; it consists of tra...
Definition: Transformation.hpp:76
MOCK_CONST_METHOD8(propagation, bool(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))
Struct to combine all parameters and settings.
Definition: Parameters.hpp:280
MOCK_METHOD1(setBriskDetectionOctaves, void(size_t octaves))
MOCK_METHOD4(detectAndDescribe, bool(size_t cameraIndex, std::shared_ptr< okvis::MultiFrame > frameOut, const okvis::kinematics::Transformation &T_WC, const std::vector< cv::KeyPoint > *keypoints))
IMU parameters.
Definition: Parameters.hpp:105
Time representation. May either represent wall clock time or ROS clock time.
Definition: Time.hpp:187
An abstract interface for backends.
Definition: VioBackendInterface.hpp:67