Merge pull request #624 from borglab/fix/213

IMU Parameters Documentation
release/4.3a0
Varun Agrawal 2020-12-01 19:04:45 -05:00 committed by GitHub
commit 873f038961
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
3 changed files with 8 additions and 4 deletions

View File

@ -29,8 +29,8 @@ namespace imuBias {
class GTSAM_EXPORT ConstantBias { class GTSAM_EXPORT ConstantBias {
private: private:
Vector3 biasAcc_; Vector3 biasAcc_; ///< The units for stddev are σ = m/s² or m √Hz/s²
Vector3 biasGyro_; Vector3 biasGyro_; ///< The units for stddev are σ = rad/s or rad √Hz/s
public: public:
/// dimension of the variable - used to autodetect sizes /// dimension of the variable - used to autodetect sizes

View File

@ -29,7 +29,9 @@ namespace gtsam {
/// Parameters for pre-integration: /// Parameters for pre-integration:
/// Usage: Create just a single Params and pass a shared pointer to the constructor /// Usage: Create just a single Params and pass a shared pointer to the constructor
struct GTSAM_EXPORT PreintegratedRotationParams { struct GTSAM_EXPORT PreintegratedRotationParams {
Matrix3 gyroscopeCovariance; ///< continuous-time "Covariance" of gyroscope measurements /// Continuous-time "Covariance" of gyroscope measurements
/// The units for stddev are σ = rad/s/√Hz
Matrix3 gyroscopeCovariance;
boost::optional<Vector3> omegaCoriolis; ///< Coriolis constant boost::optional<Vector3> omegaCoriolis; ///< Coriolis constant
boost::optional<Pose3> body_P_sensor; ///< The pose of the sensor in the body frame boost::optional<Pose3> body_P_sensor; ///< The pose of the sensor in the body frame

View File

@ -24,7 +24,9 @@ namespace gtsam {
/// Parameters for pre-integration: /// Parameters for pre-integration:
/// Usage: Create just a single Params and pass a shared pointer to the constructor /// Usage: Create just a single Params and pass a shared pointer to the constructor
struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams { struct GTSAM_EXPORT PreintegrationParams: PreintegratedRotationParams {
Matrix3 accelerometerCovariance; ///< continuous-time "Covariance" of accelerometer /// Continuous-time "Covariance" of accelerometer
/// The units for stddev are σ = m/s²/√Hz
Matrix3 accelerometerCovariance;
Matrix3 integrationCovariance; ///< continuous-time "Covariance" describing integration uncertainty Matrix3 integrationCovariance; ///< continuous-time "Covariance" describing integration uncertainty
bool use2ndOrderCoriolis; ///< Whether to use second order Coriolis integration bool use2ndOrderCoriolis; ///< Whether to use second order Coriolis integration
Vector3 n_gravity; ///< Gravity vector in nav frame Vector3 n_gravity; ///< Gravity vector in nav frame