18 #ifndef IMU_AUGMENTOR_IMU_AUGMENTOR_WRAPPER_H_
19 #define IMU_AUGMENTOR_IMU_AUGMENTOR_WRAPPER_H_
21 #include <ff_msgs/EkfState.h>
22 #include <ff_msgs/FlightMode.h>
23 #include <ff_msgs/GraphState.h>
30 #include <geometry_msgs/PoseWithCovarianceStamped.h>
31 #include <sensor_msgs/Imu.h>
50 boost::optional<std::pair<localization_common::CombinedNavState, localization_common::CombinedNavStateCovariances>>
64 bool standstill()
const;
66 std::unique_ptr<ImuAugmentor> imu_augmentor_;
67 boost::optional<localization_common::CombinedNavState> latest_combined_nav_state_;
68 boost::optional<localization_common::CombinedNavState> latest_imu_augmented_combined_nav_state_;
69 boost::optional<localization_common::CombinedNavStateCovariances> latest_covariances_;
70 boost::optional<ff_msgs::GraphState> latest_loc_msg_;
71 std::unique_ptr<gtsam::TangentPreintegration> preintegration_helper_;
73 boost::optional<bool> standstill_;
77 #endif // IMU_AUGMENTOR_IMU_AUGMENTOR_WRAPPER_H_