OKVIS ROS
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
VioFrontendInterface.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: Mar 20, 2012
30  * Author: Stefan Leutenegger (s.leutenegger@imperial.ac.uk)
31  * Modified: Andreas Forster (an.forster@gmail.com)
32  *********************************************************************************/
33 
41 #ifndef INCLUDE_OKVIS_VIOFRONTENDINTERFACE_HPP_
42 #define INCLUDE_OKVIS_VIOFRONTENDINTERFACE_HPP_
43 
44 #include <vector>
45 #include <memory>
46 
47 #include <Eigen/Core>
48 
49 #include <opencv2/core/core.hpp>
50 #include <opencv2/features2d/features2d.hpp>
51 
53 
54 #include <okvis/Measurements.hpp>
55 #include <okvis/Parameters.hpp>
56 #include <okvis/Time.hpp>
57 #include <okvis/FrameTypedefs.hpp>
59 #include <okvis/MultiFrame.hpp>
60 
61 class Estimator;
62 
64 namespace okvis {
65 
70  public:
72  }
74  }
78 
88  virtual bool detectAndDescribe(
89  size_t cameraIndex, std::shared_ptr<okvis::MultiFrame> frameOut,
91  const std::vector<cv::KeyPoint> * keypoints) = 0;
92 
104  okvis::Estimator& estimator,
105  okvis::kinematics::Transformation& T_WS_propagated,
106  const okvis::VioParameters & params,
107  const std::shared_ptr<okvis::MapPointVector> map,
108  std::shared_ptr<okvis::MultiFrame> framesInOut, bool* asKeyframe) = 0;
109 
123  virtual bool propagation(const okvis::ImuMeasurementDeque & imuMeasurements,
124  const okvis::ImuParameters & imuParams,
125  okvis::kinematics::Transformation& T_WS_propagated,
126  okvis::SpeedAndBias & speedAndBiases,
127  const okvis::Time& t_start, const okvis::Time& t_end,
128  Eigen::Matrix<double, 15, 15>* covariance,
129  Eigen::Matrix<double, 15, 15>* jacobian) const = 0;
130 
132 };
133 
134 }
135 
136 #endif /* INCLUDE_OKVIS_VIOFRONTENDINTERFACE_HPP_ */
The estimator class.
Definition: Estimator.hpp:77
std::deque< ImuMeasurement, Eigen::aligned_allocator< ImuMeasurement > > ImuMeasurementDeque
Definition: Measurements.hpp:163
virtual bool detectAndDescribe(size_t cameraIndex, std::shared_ptr< okvis::MultiFrame > frameOut, const okvis::kinematics::Transformation &T_WC, const std::vector< cv::KeyPoint > *keypoints)=0
Detection and descriptor extraction on a per image basis.
virtual bool dataAssociationAndInitialization(okvis::Estimator &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)=0
Matching as well as initialization of landmarks and state.
Header file for the MultiFrame class.
Eigen::Matrix< double, 9, 1 > SpeedAndBias
Definition: FrameTypedefs.hpp:234
This file contains the templated measurement structs, structs encapsulating Sensor data and related t...
A class that does homogeneous transformations. This relates a frame A and B: T_AB; it consists of tra...
Definition: Transformation.hpp:76
VioFrontendInterface()
Definition: VioFrontendInterface.hpp:71
Header file for the TimeBase, Time and WallTime class.
The VioFrontendInterface class is an interface for frontends.
Definition: VioFrontendInterface.hpp:69
Struct to combine all parameters and settings.
Definition: Parameters.hpp:280
IMU parameters.
Definition: Parameters.hpp:105
Header file for the Transformation class.
Time representation. May either represent wall clock time or ROS clock time.
Definition: Time.hpp:187
This file contains struct definitions that encapsulate parameters and settings.
virtual ~VioFrontendInterface()
Definition: VioFrontendInterface.hpp:73
Header file for the VioBackendInterface class.
virtual bool propagation(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) const =0
Propagates pose, speeds and biases with given IMU measurements.
This file contains useful typedefs and structs related to frames.