NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
combined_nav_state_covariances.h
Go to the documentation of this file.
1 /* Copyright (c) 2017, United States Government, as represented by the
2  * Administrator of the National Aeronautics and Space Administration.
3  *
4  * All rights reserved.
5  *
6  * The Astrobee platform is licensed under the Apache License, Version 2.0
7  * (the "License"); you may not use this file except in compliance with the
8  * License. You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14  * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15  * License for the specific language governing permissions and limitations
16  * under the License.
17  */
18 
19 #ifndef LOCALIZATION_COMMON_COMBINED_NAV_STATE_COVARIANCES_H_
20 #define LOCALIZATION_COMMON_COMBINED_NAV_STATE_COVARIANCES_H_
21 
22 #include <Eigen/Core>
23 #include <Eigen/Geometry>
24 
25 namespace localization_common {
28  public:
29  CombinedNavStateCovariances(const Eigen::Matrix<double, 6, 6>& pose_covariance,
30  const Eigen::Matrix3d& velocity_covariance,
31  const Eigen::Matrix<double, 6, 6>& bias_covariance);
34  const Eigen::Vector3d& accelerometer_bias_variances,
36  CombinedNavStateCovariances() = default;
37  // create constructor from marginals! -> put this in
38  // localization_common!
39  Confidence PoseConfidence(const double position_log_det_threshold, const double orientation_log_det_threshold) const;
40 
41  const Eigen::Matrix<double, 6, 6>& pose_covariance() const { return pose_covariance_; }
42  const Eigen::Matrix3d& velocity_covariance() const { return velocity_covariance_; }
43  const Eigen::Matrix<double, 6, 6>& bias_covariance() const { return bias_covariance_; }
44 
45  // Diagonal Accessors for Loc msg
46  Eigen::Vector3d position_variances() const { return pose_covariance_.block<3, 3>(0, 0).diagonal(); }
47  Eigen::Vector3d orientation_variances() const { return pose_covariance_.block<3, 3>(3, 3).diagonal(); }
48  Eigen::Vector3d velocity_variances() const { return velocity_covariance_.diagonal(); }
49  Eigen::Vector3d gyro_bias_variances() const { return bias_covariance_.block<3, 3>(3, 3).diagonal(); }
50  Eigen::Vector3d accel_bias_variances() const { return bias_covariance_.block<3, 3>(0, 0).diagonal(); }
51 
52  double LogDeterminantPositionCovariance() const;
53 
55 
56  private:
57  Eigen::Matrix<double, 6, 6> pose_covariance_;
58  Eigen::Matrix3d velocity_covariance_;
59  Eigen::Matrix<double, 6, 6> bias_covariance_;
60 };
61 } // namespace localization_common
62 
63 #endif // LOCALIZATION_COMMON_COMBINED_NAV_STATE_COVARIANCES_H_
localization_common
Definition: averager.h:33
localization_common::CombinedNavStateCovariances::velocity_variances
Eigen::Vector3d velocity_variances() const
Definition: combined_nav_state_covariances.h:48
localization_common::kLost
@ kLost
Definition: combined_nav_state_covariances.h:26
localization_common::CombinedNavStateCovariances::velocity_covariance
const Eigen::Matrix3d & velocity_covariance() const
Definition: combined_nav_state_covariances.h:42
localization_common::CombinedNavStateCovariances::pose_covariance
const Eigen::Matrix< double, 6, 6 > & pose_covariance() const
Definition: combined_nav_state_covariances.h:41
localization_common::CombinedNavStateCovariances::LogDeterminantPositionCovariance
double LogDeterminantPositionCovariance() const
Definition: combined_nav_state_covariances.cc:40
localization_common::CombinedNavStateCovariances::PoseConfidence
Confidence PoseConfidence(const double position_log_det_threshold, const double orientation_log_det_threshold) const
Definition: combined_nav_state_covariances.cc:48
localization_common::CombinedNavStateCovariances::LogDeterminantOrientationCovariance
double LogDeterminantOrientationCovariance() const
Definition: combined_nav_state_covariances.cc:44
localization_common::Confidence
Confidence
Definition: combined_nav_state_covariances.h:26
localization_common::CombinedNavStateCovariances::gyro_bias_variances
Eigen::Vector3d gyro_bias_variances() const
Definition: combined_nav_state_covariances.h:49
point_cloud_common::Vector3d
Eigen::Vector3d Vector3d(const PointType &point)
Definition: utilities.h:328
localization_common::CombinedNavStateCovariances::accel_bias_variances
Eigen::Vector3d accel_bias_variances() const
Definition: combined_nav_state_covariances.h:50
localization_common::CombinedNavStateCovariances::bias_covariance
const Eigen::Matrix< double, 6, 6 > & bias_covariance() const
Definition: combined_nav_state_covariances.h:43
localization_common::CombinedNavStateCovariances
Definition: combined_nav_state_covariances.h:27
localization_common::CombinedNavStateCovariances::position_variances
Eigen::Vector3d position_variances() const
Definition: combined_nav_state_covariances.h:46
localization_common::CombinedNavStateCovariances::CombinedNavStateCovariances
CombinedNavStateCovariances()=default
localization_common::kPoor
@ kPoor
Definition: combined_nav_state_covariances.h:26
localization_common::CombinedNavStateCovariances::orientation_variances
Eigen::Vector3d orientation_variances() const
Definition: combined_nav_state_covariances.h:47
localization_common::kGood
@ kGood
Definition: combined_nav_state_covariances.h:26