NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
combined_nav_state.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_H_
20 #define LOCALIZATION_COMMON_COMBINED_NAV_STATE_H_
21 
23 
24 #include <gtsam/base/Vector.h>
25 #include <gtsam/geometry/Pose3.h>
26 #include <gtsam/linear/NoiseModel.h>
27 #include <gtsam/navigation/CombinedImuFactor.h>
28 #include <gtsam/navigation/ImuBias.h>
29 #include <gtsam/navigation/NavState.h>
30 
31 namespace localization_common {
33  gtsam::SharedNoiseModel pose_noise;
34  gtsam::SharedNoiseModel velocity_noise;
35  gtsam::SharedNoiseModel bias_noise;
36 
37  private:
38  // Serialization function
40  template <class Archive>
41  void serialize(Archive& ar, const unsigned int file_version) {
42  ar& BOOST_SERIALIZATION_NVP(pose_noise);
43  ar& BOOST_SERIALIZATION_NVP(velocity_noise);
44  ar& BOOST_SERIALIZATION_NVP(bias_noise);
45  }
46 };
47 
49  public:
50  CombinedNavState(const gtsam::NavState& nav_state, const gtsam::imuBias::ConstantBias& bias, const Time timestamp);
51  CombinedNavState(const gtsam::Pose3& pose, const gtsam::Velocity3& velocity, const gtsam::imuBias::ConstantBias& bias,
52  const Time timestamp);
53  CombinedNavState() = default;
54  Time timestamp() const { return timestamp_; }
55  const gtsam::NavState& nav_state() const { return nav_state_; }
56  gtsam::Pose3 pose() const { return nav_state().pose(); }
57  const gtsam::Velocity3& velocity() const { return nav_state().velocity(); }
58  const gtsam::imuBias::ConstantBias& bias() const { return bias_; }
59 
60  private:
61  // Serialization function
63  template <class Archive>
64  void serialize(Archive& ar, const unsigned int file_version) {
65  ar& BOOST_SERIALIZATION_NVP(nav_state_);
66  ar& BOOST_SERIALIZATION_NVP(bias_);
67  ar& BOOST_SERIALIZATION_NVP(timestamp_);
68  }
69 
70  gtsam::NavState nav_state_;
71  gtsam::imuBias::ConstantBias bias_;
72  Time timestamp_;
73 };
74 
75 } // namespace localization_common
76 
77 #endif // LOCALIZATION_COMMON_COMBINED_NAV_STATE_H_
localization_common
Definition: averager.h:33
localization_common::CombinedNavState
Definition: combined_nav_state.h:48
localization_common::CombinedNavState::timestamp
Time timestamp() const
Definition: combined_nav_state.h:54
localization_common::CombinedNavStateNoise::access
friend class boost::serialization::access
Definition: combined_nav_state.h:39
time.h
localization_common::CombinedNavState::velocity
const gtsam::Velocity3 & velocity() const
Definition: combined_nav_state.h:57
localization_common::CombinedNavState::nav_state
const gtsam::NavState & nav_state() const
Definition: combined_nav_state.h:55
localization_common::CombinedNavStateNoise
Definition: combined_nav_state.h:32
localization_common::CombinedNavState::bias
const gtsam::imuBias::ConstantBias & bias() const
Definition: combined_nav_state.h:58
localization_common::CombinedNavStateNoise::bias_noise
gtsam::SharedNoiseModel bias_noise
Definition: combined_nav_state.h:35
localization_common::CombinedNavState::access
friend class boost::serialization::access
Definition: combined_nav_state.h:62
localization_common::CombinedNavState::pose
gtsam::Pose3 pose() const
Definition: combined_nav_state.h:56
localization_common::CombinedNavStateNoise::pose_noise
gtsam::SharedNoiseModel pose_noise
Definition: combined_nav_state.h:33
localization_common::CombinedNavState::CombinedNavState
CombinedNavState()=default
localization_common::CombinedNavStateNoise::velocity_noise
gtsam::SharedNoiseModel velocity_noise
Definition: combined_nav_state.h:34
localization_common::Time
double Time
Definition: time.h:23