NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
graph_vio.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 GRAPH_VIO_GRAPH_VIO_H_
20 #define GRAPH_VIO_GRAPH_VIO_H_
21 
36 
37 #include <boost/serialization/serialization.hpp>
38 
39 namespace graph_vio {
40 // Siding window graph optimizer that uses IMU and optical flow feature point measurements
41 // with VO smart projection factors to perform VIO.
42 // Uses the CombinedNavStateNodeAdder to add relative IMU factors between graph nodes.
43 // Also adds standstill pose and velocity factors when standstill is detected
44 // using the history of feature point measurements.
46  public:
47  explicit GraphVIO(const GraphVIOParams& params);
48 
49  // For Serialization Only
50  GraphVIO() {}
51 
52  // Adds imu measurement to combined nav state node adder.
54 
55  // Sets the fan speed mode in the combined nav state node model's IMU integrator
56  void SetFanSpeedMode(const localization_measurements::FanSpeedMode& fan_speed_mode);
57 
58  // Adds feature points measurement to vo smart projection factor adder.
60  const localization_measurements::FeaturePointsMeasurement& feature_points_measurement);
61 
62  // Adds depth odometry measurement for depth odometry relative pose factor adder.
64  const localization_measurements::DepthOdometryMeasurement& depth_odometry_measurement);
65 
66  // Returns a const reference to combined nav state nodes.
68 
69  // Returns whether standstill is detected or not.
70  bool standstill() const;
71 
72  // Const accesor to feature tracker used for smart factor creation
74 
75  // Construct pose covariance interpolater using latest marginals and nodes
76  std::shared_ptr<localization_common::MarginalsPoseCovarianceInterpolater<nodes::CombinedNavStateNodes>>
78 
79  private:
80  // Uses the latest feature track points to detect standstill.
81  bool CheckForStandstill(const localization_common::Time oldest_allowed_time);
82 
83  // bool ValidGraph() const final;
84 
85  // Serialization function
87  template <class Archive>
88  void serialize(Archive& ar, const unsigned int file_version) {
89  ar& BOOST_SERIALIZATION_BASE_OBJECT_NVP(sliding_window_graph_optimizer::SlidingWindowGraphOptimizer);
90  ar& BOOST_SERIALIZATION_NVP(params_);
91  ar& BOOST_SERIALIZATION_NVP(vo_smart_projection_factor_adder_);
92  ar& BOOST_SERIALIZATION_NVP(standstill_factor_adder_);
93  ar& BOOST_SERIALIZATION_NVP(depth_odometry_factor_adder_);
94  ar& BOOST_SERIALIZATION_NVP(combined_nav_state_node_adder_);
95  }
96 
97  GraphVIOParams params_;
98  std::shared_ptr<node_adders::CombinedNavStateNodeAdder> combined_nav_state_node_adder_;
99  bool standstill_;
100 
101  // Factor Adders
102  std::shared_ptr<factor_adders::DepthOdometryFactorAdder<node_adders::CombinedNavStateNodeAdder>>
103  depth_odometry_factor_adder_;
104  std::shared_ptr<factor_adders::VoSmartProjectionFactorAdder<node_adders::CombinedNavStateNodeAdder>>
105  vo_smart_projection_factor_adder_;
106  std::shared_ptr<factor_adders::StandstillFactorAdder<node_adders::CombinedNavStateNodeAdder>>
107  standstill_factor_adder_;
108 
109  // Node Adders
110  // std::shared_ptr<node_adders::CombinedNavStateNodeAdder> combined_nav_state_node_adder_;
111 };
112 } // namespace graph_vio
113 
114 #endif // GRAPH_VIO_GRAPH_VIO_H_
marginals_pose_covariance_interpolater.h
depth_odometry_measurement.h
localization_measurements::ImuMeasurement
Definition: imu_measurement.h:30
graph_vio::GraphVIO::standstill
bool standstill() const
Definition: graph_vio.cc:86
sliding_window_graph_optimizer.h
graph_vio::GraphVIO::GraphVIO
GraphVIO()
Definition: graph_vio.h:50
graph_vio::GraphVIO::AddFeaturePointsMeasurement
void AddFeaturePointsMeasurement(const localization_measurements::FeaturePointsMeasurement &feature_points_measurement)
Definition: graph_vio.cc:60
graph_vio::GraphVIO::combined_nav_state_nodes
const nodes::CombinedNavStateNodes & combined_nav_state_nodes() const
Definition: graph_vio.cc:82
vision_common::SpacedFeatureTracker
Definition: spaced_feature_tracker.h:32
graph_vio::GraphVIO::feature_tracker
const vision_common::SpacedFeatureTracker & feature_tracker() const
Definition: graph_vio.cc:88
nodes::CombinedNavStateNodes
Definition: combined_nav_state_nodes.h:25
combined_nav_state_node_adder.h
graph_vio::GraphVIOParams
Definition: graph_vio_params.h:34
feature_tracker.h
graph_vio::GraphVIO
Definition: graph_vio.h:45
graph_vio::GraphVIO::MarginalsPoseCovarianceInterpolater
std::shared_ptr< localization_common::MarginalsPoseCovarianceInterpolater< nodes::CombinedNavStateNodes > > MarginalsPoseCovarianceInterpolater()
Definition: graph_vio.cc:93
standstill_factor_adder.h
localization_measurements::DepthOdometryMeasurement
Definition: depth_odometry_measurement.h:28
graph_vio::GraphVIO::AddImuMeasurement
void AddImuMeasurement(const localization_measurements::ImuMeasurement &imu_measurement)
Definition: graph_vio.cc:52
graph_vio
Definition: graph_vio.h:39
depth_odometry_factor_adder.h
localization_measurements::FanSpeedMode
FanSpeedMode
Definition: fan_speed_mode.h:23
graph_vio::GraphVIO::SetFanSpeedMode
void SetFanSpeedMode(const localization_measurements::FanSpeedMode &fan_speed_mode)
Definition: graph_vio.cc:56
graph_optimizer::GraphOptimizer::params
const GraphOptimizerParams & params() const
Definition: graph_optimizer.cc:96
sliding_window_graph_optimizer::SlidingWindowGraphOptimizer
Definition: sliding_window_graph_optimizer.h:41
feature_points_measurement.h
standstill_measurement.h
imu_measurement.h
localization_common::Time
double Time
Definition: time.h:23
fan_speed_mode.h
combined_nav_state_nodes.h
localization_measurements::FeaturePointsMeasurement
Definition: feature_points_measurement.h:29
graph_vio_params.h
vo_smart_projection_factor_adder.h
graph_vio::GraphVIO::access
friend class boost::serialization::access
Definition: graph_vio.h:86
graph_vio::GraphVIO::AddDepthOdometryMeasurement
void AddDepthOdometryMeasurement(const localization_measurements::DepthOdometryMeasurement &depth_odometry_measurement)
Definition: graph_vio.cc:74