|
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
Go to the documentation of this file.
19 #ifndef GRAPH_VIO_GRAPH_VIO_H_
20 #define GRAPH_VIO_GRAPH_VIO_H_
37 #include <boost/serialization/serialization.hpp>
76 std::shared_ptr<localization_common::MarginalsPoseCovarianceInterpolater<nodes::CombinedNavStateNodes>>
87 template <
class Archive>
88 void serialize(Archive& ar,
const unsigned int file_version) {
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_);
98 std::shared_ptr<node_adders::CombinedNavStateNodeAdder> combined_nav_state_node_adder_;
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_;
114 #endif // GRAPH_VIO_GRAPH_VIO_H_
Definition: imu_measurement.h:30
bool standstill() const
Definition: graph_vio.cc:86
GraphVIO()
Definition: graph_vio.h:50
void AddFeaturePointsMeasurement(const localization_measurements::FeaturePointsMeasurement &feature_points_measurement)
Definition: graph_vio.cc:60
const nodes::CombinedNavStateNodes & combined_nav_state_nodes() const
Definition: graph_vio.cc:82
Definition: spaced_feature_tracker.h:32
const vision_common::SpacedFeatureTracker & feature_tracker() const
Definition: graph_vio.cc:88
Definition: combined_nav_state_nodes.h:25
Definition: graph_vio_params.h:34
Definition: graph_vio.h:45
std::shared_ptr< localization_common::MarginalsPoseCovarianceInterpolater< nodes::CombinedNavStateNodes > > MarginalsPoseCovarianceInterpolater()
Definition: graph_vio.cc:93
Definition: depth_odometry_measurement.h:28
void AddImuMeasurement(const localization_measurements::ImuMeasurement &imu_measurement)
Definition: graph_vio.cc:52
Definition: graph_vio.h:39
FanSpeedMode
Definition: fan_speed_mode.h:23
void SetFanSpeedMode(const localization_measurements::FanSpeedMode &fan_speed_mode)
Definition: graph_vio.cc:56
const GraphOptimizerParams & params() const
Definition: graph_optimizer.cc:96
Definition: sliding_window_graph_optimizer.h:41
double Time
Definition: time.h:23
Definition: feature_points_measurement.h:29
friend class boost::serialization::access
Definition: graph_vio.h:86
void AddDepthOdometryMeasurement(const localization_measurements::DepthOdometryMeasurement &depth_odometry_measurement)
Definition: graph_vio.cc:74