OKVIS ROS
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
Measurements.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 22, 2014
30  * Author: Stefan Leutenegger (s.leutenegger@imperial.ac.uk)
31  *********************************************************************************/
32 
40 #ifndef INCLUDE_OKVIS_MEASUREMENTS_HPP_
41 #define INCLUDE_OKVIS_MEASUREMENTS_HPP_
42 
43 #include <deque>
44 #include <vector>
45 #include <memory>
46 #pragma GCC diagnostic push
47 #pragma GCC diagnostic ignored "-Wnon-virtual-dtor"
48 #pragma GCC diagnostic push
49 #pragma GCC diagnostic ignored "-Woverloaded-virtual"
50 #include <opencv2/opencv.hpp>
51 #pragma GCC diagnostic pop
52 #pragma GCC diagnostic pop
53 #include <Eigen/Dense>
54 #include <okvis/Time.hpp>
56 
58 namespace okvis {
66 template<class MEASUREMENT_T>
67 struct Measurement {
68  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
70  MEASUREMENT_T measurement;
71  int sensorId = -1;
72 
75  : timeStamp(0.0) {
76  }
83  Measurement(const okvis::Time& timeStamp_, const MEASUREMENT_T& measurement_,
84  int sensorId = -1)
85  : timeStamp(timeStamp_),
86  measurement(measurement_),
88  }
89 };
90 
93  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
96  : gyroscopes(),
97  accelerometers() {
98  }
104  ImuSensorReadings(Eigen::Vector3d gyroscopes_,
105  Eigen::Vector3d accelerometers_)
106  : gyroscopes(gyroscopes_),
107  accelerometers(accelerometers_) {
108  }
109  Eigen::Vector3d gyroscopes;
110  Eigen::Vector3d accelerometers;
111 };
112 
115  cv::Mat image;
116  cv::Mat depthImage;
117  std::vector<cv::KeyPoint> keypoints;
119 };
120 
123  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
124  Eigen::Vector3d position;
125  Eigen::Vector3d positionOffset;
126  Eigen::Matrix3d positionCovariance;
127 };
128 
131  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
132  double lat_wgs84;
133  double lon_wgs84;
134  double alt_wgs84;
136  Eigen::Matrix3d positionCovarianceENU;
137 };
138 
141  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
143  Eigen::Vector3d fluxDensity;
144 };
145 
148  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
149  double pressure;
150  double temperature;
151 };
152 
155  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
156  double pressure;
157  Eigen::Vector3d acceleration_B;
158 };
159 
160 // this is how we store raw measurements before more advanced filling into
161 // data structures happens:
163 typedef std::deque<ImuMeasurement, Eigen::aligned_allocator<ImuMeasurement> > ImuMeasurementDeque;
165 struct CameraData {
166  cv::Mat image;
167  std::vector<cv::KeyPoint> keypoints;
169 };
171 struct KeypointData {
172  std::vector<cv::KeyPoint> keypoints;
173  std::vector<long unsigned int> landmarkIds;
174  cv::Mat descriptors;
175 };
177 struct FrameData {
178  typedef std::shared_ptr<okvis::FrameData> Ptr;
181 };
185 
187 typedef std::deque<PositionMeasurement,
188  Eigen::aligned_allocator<PositionMeasurement> > PositionMeasurementDeque;
189 
191 typedef std::deque<GpsPositionMeasurement,
192  Eigen::aligned_allocator<GpsPositionMeasurement> > GpsPositionMeasurementDeque;
193 
195 typedef std::deque<MagnetometerMeasurement,
196  Eigen::aligned_allocator<MagnetometerMeasurement> > MagnetometerMeasurementDeque;
197 
199 
201 
202 typedef Eigen::Matrix<double, 9, 1> SpeedAndBias;
203 
204 } // namespace okvis
205 
206 #endif // INCLUDE_OKVIS_MEASUREMENTS_HPP_
std::deque< PositionMeasurement, Eigen::aligned_allocator< PositionMeasurement > > PositionMeasurementDeque
Definition: Measurements.hpp:188
Measurement< DifferentialPressureReading > DifferentialPressureMeasurement
Definition: Measurements.hpp:200
Measurement< GpsPositionReading > GpsPositionMeasurement
Definition: Measurements.hpp:190
Keypoint measurement.
Definition: Measurements.hpp:171
std::shared_ptr< okvis::FrameData > Ptr
Definition: Measurements.hpp:178
ImuSensorReadings(Eigen::Vector3d gyroscopes_, Eigen::Vector3d accelerometers_)
Constructor.
Definition: Measurements.hpp:104
KeypointData keypoints
Keypoints.
Definition: Measurements.hpp:180
Measurement< BarometerReading > BarometerMeasurement
Definition: Measurements.hpp:198
std::deque< ImuMeasurement, Eigen::aligned_allocator< ImuMeasurement > > ImuMeasurementDeque
Definition: Measurements.hpp:163
Measurement< CameraData > CameraMeasurement
Definition: Measurements.hpp:182
cv::Mat image
Grayscale/RGB image.
Definition: Measurements.hpp:115
std::deque< MagnetometerMeasurement, Eigen::aligned_allocator< MagnetometerMeasurement > > MagnetometerMeasurementDeque
Definition: Measurements.hpp:196
Camera measurement.
Definition: Measurements.hpp:165
cv::Mat depthImage
Depth image.
Definition: Measurements.hpp:116
Eigen::Vector3d gyroscopes
Gyroscope measurement.
Definition: Measurements.hpp:109
Eigen::Vector3d accelerometers
Accelerometer measurement.
Definition: Measurements.hpp:110
Eigen::Matrix< double, 9, 1 > SpeedAndBias
Definition: FrameTypedefs.hpp:234
std::vector< long unsigned int > landmarkIds
Associated landmark IDs.
Definition: Measurements.hpp:173
cv::Mat descriptors
Keypoint descriptors.
Definition: Measurements.hpp:174
Measurement< MagnetometerReading > MagnetometerMeasurement
Definition: Measurements.hpp:194
Measurement< FrameData > FrameMeasurement
Definition: Measurements.hpp:183
IMU measurements. For now assume they are synchronized:
Definition: Measurements.hpp:92
Header file for the TimeBase, Time and WallTime class.
Barometer measurement.
Definition: Measurements.hpp:147
Magnetometer measurement.
Definition: Measurements.hpp:140
Measurement(const okvis::Time &timeStamp_, const MEASUREMENT_T &measurement_, int sensorId=-1)
Constructor.
Definition: Measurements.hpp:83
EIGEN_MAKE_ALIGNED_OPERATOR_NEW double lat_wgs84
Latitude in WGS84 coordinate system.
Definition: Measurements.hpp:132
double lon_wgs84
Longitude in WGS84 coordiante system.
Definition: Measurements.hpp:133
Frame measurement.
Definition: Measurements.hpp:177
std::vector< cv::KeyPoint > keypoints
Keypoints if available.
Definition: Measurements.hpp:167
double temperature
Temperature. [K].
Definition: Measurements.hpp:150
CameraData image
Camera measurement, i.e., image.
Definition: Measurements.hpp:179
bool deliversKeypoints
Are the keypoints delivered too?
Definition: Measurements.hpp:168
cv::Mat image
Image.
Definition: Measurements.hpp:166
std::vector< cv::KeyPoint > keypoints
Keypoints if available.
Definition: Measurements.hpp:117
double alt_wgs84
Altitude in WGS84 coordinate system.
Definition: Measurements.hpp:134
int sensorId
Sensor ID. E.g. camera index in a multicamera setup.
Definition: Measurements.hpp:71
Measurement< ImuSensorReadings > ImuMeasurement
Definition: Measurements.hpp:162
EIGEN_MAKE_ALIGNED_OPERATOR_NEW okvis::Time timeStamp
Measurement timestamp.
Definition: Measurements.hpp:69
Generic measurements.
Definition: Measurements.hpp:67
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d position
Position measurement.
Definition: Measurements.hpp:124
Eigen::Vector3d positionOffset
Position offset.
Definition: Measurements.hpp:125
Depth camera measurements. For now assume they are synchronized:
Definition: Measurements.hpp:114
Measurement< DepthCameraData > DepthCameraMeasurement
Definition: Measurements.hpp:184
double geoidSeparation
Separation between geoid (MSL) and WGS-84 ellipsoid. [m].
Definition: Measurements.hpp:135
Position measurement.
Definition: Measurements.hpp:122
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d fluxDensity
< The magnetic flux density measurement. [uT]
Definition: Measurements.hpp:143
EIGEN_MAKE_ALIGNED_OPERATOR_NEW double pressure
Pressure measurement. [Pa].
Definition: Measurements.hpp:149
Eigen::Vector3d acceleration_B
Acceleration in B-frame.
Definition: Measurements.hpp:157
Header file for the Transformation class.
MEASUREMENT_T measurement
Actual measurement.
Definition: Measurements.hpp:70
Differential pressure sensor measurement.
Definition: Measurements.hpp:154
Eigen::Matrix3d positionCovariance
Measurement covariance.
Definition: Measurements.hpp:126
Time representation. May either represent wall clock time or ROS clock time.
Definition: Time.hpp:187
std::vector< cv::KeyPoint > keypoints
Keypoints.
Definition: Measurements.hpp:172
bool deliversKeypoints
Are keypoints already delievered in measurement?
Definition: Measurements.hpp:118
GPS position measurement.
Definition: Measurements.hpp:130
Measurement< PositionReading > PositionMeasurement
Definition: Measurements.hpp:186
std::deque< GpsPositionMeasurement, Eigen::aligned_allocator< GpsPositionMeasurement > > GpsPositionMeasurementDeque
Definition: Measurements.hpp:192
Measurement()
Default constructor.
Definition: Measurements.hpp:74
EIGEN_MAKE_ALIGNED_OPERATOR_NEW double pressure
Pressure measurement. [Pa].
Definition: Measurements.hpp:156
Eigen::Matrix3d positionCovarianceENU
Measurement covariance. East/North/Up.
Definition: Measurements.hpp:136
EIGEN_MAKE_ALIGNED_OPERATOR_NEW ImuSensorReadings()
Default constructor.
Definition: Measurements.hpp:95