41 #ifndef INCLUDE_OKVIS_PARAMETERS_HPP_
42 #define INCLUDE_OKVIS_PARAMETERS_HPP_
46 #pragma GCC diagnostic push
47 #pragma GCC diagnostic ignored "-Woverloaded-virtual"
48 #include <opencv2/opencv.hpp>
49 #pragma GCC diagnostic pop
50 #include <Eigen/Dense>
83 : sigma_absolute_translation(sigma_absolute_translation),
84 sigma_absolute_orientation(sigma_absolute_orientation),
85 sigma_c_relative_translation(sigma_c_relative_translation),
86 sigma_c_relative_orientation(sigma_c_relative_orientation)
106 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
129 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
144 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
155 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
167 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
205 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
267 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
281 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
301 #endif // INCLUDE_OKVIS_PARAMETERS_HPP_
double sigma_aw_c
Accelerometer drift noise density.
Definition: Parameters.hpp:115
ExtrinsicsEstimationParameters camera_extrinsics
Camera extrinsic estimation parameters.
Definition: Parameters.hpp:285
MagnetometerParameters magnetometer
Magnetometer parameters.
Definition: Parameters.hpp:288
Magnetic ENU z bias.
Definition: Parameters.hpp:166
Header file for the NCameraSystem class.
Differential pressure sensor parameters.
Definition: Parameters.hpp:204
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d antennaOffset
The position offset of the antenna in body (B) coordinates.
Definition: Parameters.hpp:145
double updateFrequency
Related state estimates are inserted at this frequency. [Hz].
Definition: Parameters.hpp:171
MagneticEnuZParameters magnetic_enu_z
Dynamics of magnetic ENU z component variation.
Definition: Parameters.hpp:291
okvis::kinematics::Transformation T_Wc_W
Provide custom World frame Wc.
Definition: Parameters.hpp:274
ExtrinsicsEstimationParameters(double sigma_absolute_translation, double sigma_absolute_orientation, double sigma_c_relative_translation, double sigma_c_relative_orientation)
Constructor.
Definition: Parameters.hpp:79
Eigen::VectorXd c_minus_z_of_alpha
Definition: Parameters.hpp:213
double temperatureStdev
Measurement (white noise part) standard deviation. [kPa].
Definition: Parameters.hpp:182
Struct to define the behavior of the camera extrinsics.
Definition: Parameters.hpp:60
double timeLimitForMatchingAndOptimization
The time limit for both matching and optimization. [s].
Definition: Parameters.hpp:238
GpsParameters gps
GPS parameters.
Definition: Parameters.hpp:290
double tau
Reversion time constant of accerometer bias. [s].
Definition: Parameters.hpp:116
Some visualization settings.
Definition: Parameters.hpp:259
double sigma_c
ENU z-component noise density. [uT/s/sqrt(Hz)].
Definition: Parameters.hpp:169
GPS parameters.
Definition: Parameters.hpp:143
double staticPressureStdev
Measurement (white noise part) standard deviation. [kPa].
Definition: Parameters.hpp:181
bool publishImuPropagatedState
Should the state that is propagated with IMU messages be published? Or just the optimized ones...
Definition: Parameters.hpp:273
double sigma_c
Drift noise density. [m/s/sqrt(s)].
Definition: Parameters.hpp:227
double g_max
Gyroscope saturation. [rad/s].
Definition: Parameters.hpp:109
double tau
Reversion time constant. [s].
Definition: Parameters.hpp:194
Header file for the MultiFrame class.
double accelerationStdev
Definition: Parameters.hpp:209
int min_iterations
Minimum iterations the optimization should perform.
Definition: Parameters.hpp:237
double tau
Reversion time constant of bias [s].
Definition: Parameters.hpp:132
double A
Reference wing area. [m^2].
Definition: Parameters.hpp:216
int rate
IMU rate in Hz.
Definition: Parameters.hpp:119
Visualization visualization
Visualization parameters.
Definition: Parameters.hpp:283
double sigma_c
Bias noise density [uT/sqrt(Hz)].
Definition: Parameters.hpp:133
double detectionThreshold
Keypoint detection threshold.
Definition: Parameters.hpp:240
int max_iterations
Maximum iterations the optimization should perform.
Definition: Parameters.hpp:236
double m
Mass. [kg].
Definition: Parameters.hpp:215
int maxNoKeypoints
Restrict to a maximum of this many keypoints per image (strongest ones).
Definition: Parameters.hpp:243
Header file for the TimeBase, Time and WallTime class.
double g
Earth acceleration.
Definition: Parameters.hpp:117
A class that assembles multiple cameras into a system of (potentially different) cameras.
Definition: NCameraSystem.hpp:61
PositionSensorParameters position
Position sensor parameters.
Definition: Parameters.hpp:289
Some publishing parameters.
Definition: Parameters.hpp:266
FrameName velocitiesFrame
B or S, the frames in which the velocities of the selected trackedBodyFrame will be expressed in...
Definition: Parameters.hpp:276
ExtrinsicsEstimationParameters()
Default Constructor – fixed camera extrinsics.
Definition: Parameters.hpp:64
float landmarkQualityThreshold
Quality threshold under which landmarks are not published. Between 0 and 1.
Definition: Parameters.hpp:270
Parameters for optimization and related things (detection).
Definition: Parameters.hpp:235
double a_max
Accelerometer saturation. [m/s^2].
Definition: Parameters.hpp:108
double priorStdev
Prior. [uT].
Definition: Parameters.hpp:131
Position sensor parameters.
Definition: Parameters.hpp:154
ImuParameters imu
IMU parameters.
Definition: Parameters.hpp:287
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Eigen::Vector3d positionSensorOffset
The position offset of the position sensor in body (B) coordinates.
Definition: Parameters.hpp:156
Barometer parameters.
Definition: Parameters.hpp:180
double tau
Reversion time constant of ENU z-component. [s].
Definition: Parameters.hpp:170
double sigma_gw_c
Gyroscope drift noise density.
Definition: Parameters.hpp:114
QFF parameters.
Definition: Parameters.hpp:191
okvis::Duration timeReserve
Store a little more on the beginning and end of the IMU buffer. [s].
Definition: Parameters.hpp:239
SensorsInformation sensors_information
Information on camera and IMU setup.
Definition: Parameters.hpp:284
double c_y_of_beta
Polynomial (only proportionality) for y direction (dimensionless) force, beta deg.
Definition: Parameters.hpp:214
double updateFrequency
Related state estimates are inserted at this frequency. [Hz].
Definition: Parameters.hpp:195
int numKeyframes
Number of keyframes.
Definition: Parameters.hpp:244
double sigma_absolute_orientation
Absolute orientation stdev. [rad].
Definition: Parameters.hpp:92
Struct to combine all parameters and settings.
Definition: Parameters.hpp:280
int numImuFrames
Number of IMU frames.
Definition: Parameters.hpp:245
EIGEN_MAKE_ALIGNED_OPERATOR_NEW Optimization optimization
Optimization parameters.
Definition: Parameters.hpp:282
double priorStdev
Prior of QFF [kPa].
Definition: Parameters.hpp:192
WindParameters wind
Wind parameters.
Definition: Parameters.hpp:295
double priorStdev
Prior of wind. [m/s].
Definition: Parameters.hpp:226
double updateFrequency
Related state estimates are inserted at this frequency. [Hz].
Definition: Parameters.hpp:134
EIGEN_MAKE_ALIGNED_OPERATOR_NEW double priorStdev
ENU z-component bias prior. [uT].
Definition: Parameters.hpp:168
Eigen::Vector3d a0
Mean of the prior accelerometer bias.
Definition: Parameters.hpp:118
Duration representation for use with the Time class.
Definition: Duration.hpp:131
bool displayImages
Display images?
Definition: Parameters.hpp:260
Magnetometer parameters.
Definition: Parameters.hpp:128
float maxLandmarkQuality
Quality above which landmarks are assumed to be of the best quality. Between 0 and 1...
Definition: Parameters.hpp:271
double sigma_g_c
Gyroscope noise density.
Definition: Parameters.hpp:110
IMU parameters.
Definition: Parameters.hpp:105
double sigma_absolute_translation
Absolute translation stdev. [m].
Definition: Parameters.hpp:91
bool publishLandmarks
Select, if you want to publish landmarks at all.
Definition: Parameters.hpp:269
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int publishRate
Maximum publishing rate. [Hz].
Definition: Parameters.hpp:268
PublishingParameters publishing
Publishing parameters.
Definition: Parameters.hpp:296
double sigma_bg
Initial gyroscope bias.
Definition: Parameters.hpp:111
double sigma_c_relative_orientation
Relative orientation noise density. [rad/sqrt(Hz)].
Definition: Parameters.hpp:96
okvis::cameras::NCameraSystem nCameraSystem
Camera configuration.
Definition: Parameters.hpp:286
double sigma_a_c
Accelerometer noise density.
Definition: Parameters.hpp:112
int detectionOctaves
Number of keypoint detection octaves.
Definition: Parameters.hpp:242
bool isLeveled
If true, the position sensor measurements are assumed to be world z up (exactly, i.e. only yaw gets estimated).
Definition: Parameters.hpp:157
bool useMedianFilter
Use a Median filter over captured image?
Definition: Parameters.hpp:241
size_t maxPathLength
Maximum length of ros::nav_mgsgs::Path to be published.
Definition: Parameters.hpp:272
BarometerParameters barometer
Barometer parameters.
Definition: Parameters.hpp:292
Wind parameters.
Definition: Parameters.hpp:225
DifferentialPressureSensorParameters differential
Differential pressure sensor parameters.
Definition: Parameters.hpp:294
double sigma_c
Drift noise density. [kPa/sqrt(s)].
Definition: Parameters.hpp:193
QffParameters qff
QFF parameters.
Definition: Parameters.hpp:293
FrameName
Definition: Parameters.hpp:263
double sigma_ba
Initial accelerometer bias.
Definition: Parameters.hpp:113
double sigma_c_relative_translation
Relative translation noise density. [m/sqrt(Hz)].
Definition: Parameters.hpp:95
double tau
Reversion time constant. [s];.
Definition: Parameters.hpp:228
EIGEN_MAKE_ALIGNED_OPERATOR_NEW double differentialPressureStdev
Definition: Parameters.hpp:206
FrameName trackedBodyFrame
B or S, the frame of reference that will be expressed relative to the selected worldFrame Wc...
Definition: Parameters.hpp:275
EIGEN_MAKE_ALIGNED_OPERATOR_NEW okvis::kinematics::Transformation T_BS
Transformation from Body frame to IMU (sensor frame S).
Definition: Parameters.hpp:107
EIGEN_MAKE_ALIGNED_OPERATOR_NEW double stdev
Measurement (white noise part) standard deviation. [uT].
Definition: Parameters.hpp:130
double updateFrequency
Related state estimates are inserted at this frequency. [Hz].
Definition: Parameters.hpp:229