|  | NASA Astrobee Robot Software
    0.19.1
    Flight software for the Astrobee robots operating inside the International Space Station. | 
| Functions | |
| void | LoadImuIntegratorParams (config_reader::ConfigReader &config, ImuIntegratorParams ¶ms) | 
| void | LoadImuFilterParams (config_reader::ConfigReader &config, ImuFilterParams ¶ms) | 
| std::unique_ptr< Filter > | LoadFilter (const std::string &filter_type) | 
| ImuIntegratorParams | DefaultImuIntegratorParams () | 
| std::vector< localization_measurements::ImuMeasurement > | ConstantMeasurements (const Eigen::Vector3d &acceleration, const Eigen::Vector3d &angular_velocity, const int num_measurements, const localization_common::Time start_time, const double time_increment) | 
| gtsam::Rot3 | IntegrateAngularVelocities (const std::vector< localization_measurements::ImuMeasurement > &imu_measurements, const gtsam::Rot3 &starting_orientation, const localization_common::Time starting_time) | 
| sensor_msgs::Imu | ImuMsg (const localization_measurements::ImuMeasurement &imu_measurement) | 
| boost::optional< localization_measurements::ImuMeasurement > | Interpolate (const localization_measurements::ImuMeasurement &imu_measurement_a, const localization_measurements::ImuMeasurement &imu_measurement_b, const localization_common::Time timestamp) | 
| gtsam::PreintegratedCombinedMeasurements | Pim (const gtsam::imuBias::ConstantBias &bias, const boost::shared_ptr< gtsam::PreintegratedCombinedMeasurements::Params > ¶ms) | 
| void | AddMeasurement (const localization_measurements::ImuMeasurement &imu_measurement, localization_common::Time &last_added_imu_measurement_time, gtsam::PreintegratedCombinedMeasurements &pim) | 
| localization_common::CombinedNavState | PimPredict (const localization_common::CombinedNavState &combined_nav_state, const gtsam::PreintegratedCombinedMeasurements &pim) | 
| using imu_integration::ButterO1S125Lp3N33_33 = typedef ButterO1<ParamsButterO1S125Lp3N33_33> | 
| using imu_integration::ButterO1S125Lp3N41_66 = typedef ButterO1<ParamsButterO1S125Lp3N41_66> | 
| using imu_integration::ButterO1S125Lp3N46_66 = typedef ButterO1<ParamsButterO1S125Lp3N46_66> | 
| using imu_integration::ButterO1S62_5Lp3N15_83 = typedef ButterO1<ParamsButterO1S62_5Lp3N15_83> | 
| using imu_integration::ButterO1S62_5Lp3N20_83 = typedef ButterO1<ParamsButterO1S62_5Lp3N20_83> | 
| using imu_integration::ButterO1S62_5Lp3N29_16 = typedef ButterO1<ParamsButterO1S62_5Lp3N29_16> | 
| using imu_integration::ButterO3S125Lp3N33_33 = typedef ButterO3<ParamsButterO3S125Lp3N33_33> | 
| using imu_integration::ButterO3S125Lp3N41_66 = typedef ButterO3<ParamsButterO3S125Lp3N41_66> | 
| using imu_integration::ButterO3S125Lp3N46_66 = typedef ButterO3<ParamsButterO3S125Lp3N46_66> | 
| using imu_integration::ButterO3S62_5Lp3N15_83 = typedef ButterO3<ParamsButterO3S62_5Lp3N15_83> | 
| using imu_integration::ButterO3S62_5Lp3N20_83 = typedef ButterO3<ParamsButterO3S62_5Lp3N20_83> | 
| using imu_integration::ButterO3S62_5Lp3N29_16 = typedef ButterO3<ParamsButterO3S62_5Lp3N29_16> | 
| using imu_integration::ButterO5S125Lp3N33_33 = typedef ButterO5<ParamsButterO5S125Lp3N33_33> | 
| using imu_integration::ButterO5S125Lp3N41_66 = typedef ButterO5<ParamsButterO5S125Lp3N41_66> | 
| using imu_integration::ButterO5S125Lp3N46_66 = typedef ButterO5<ParamsButterO5S125Lp3N46_66> | 
| using imu_integration::ButterO5S62_5Lp1N29_16 = typedef ButterO5<ParamsButterO5S62_5Lp1N29_16> | 
| using imu_integration::ButterO5S62_5Lp3N15_83 = typedef ButterO5<ParamsButterO5S62_5Lp3N15_83> | 
| using imu_integration::ButterO5S62_5Lp3N20_83 = typedef ButterO5<ParamsButterO5S62_5Lp3N20_83> | 
| using imu_integration::ButterO5S62_5Lp3N29_16 = typedef ButterO5<ParamsButterO5S62_5Lp3N29_16> | 
| using imu_integration::ButterO7S62_5Lp3N20_83 = typedef ButterO7<ParamsButterO7S62_5Lp3N20_83> | 
| void imu_integration::AddMeasurement | ( | const localization_measurements::ImuMeasurement & | imu_measurement, | 
| localization_common::Time & | last_added_imu_measurement_time, | ||
| gtsam::PreintegratedCombinedMeasurements & | pim | ||
| ) | 
| std::vector< lm::ImuMeasurement > imu_integration::ConstantMeasurements | ( | const Eigen::Vector3d & | acceleration, | 
| const Eigen::Vector3d & | angular_velocity, | ||
| const int | num_measurements, | ||
| const localization_common::Time | start_time, | ||
| const double | time_increment | ||
| ) | 
| ImuIntegratorParams imu_integration::DefaultImuIntegratorParams | ( | ) | 
| sensor_msgs::Imu imu_integration::ImuMsg | ( | const localization_measurements::ImuMeasurement & | imu_measurement | ) | 
| gtsam::Rot3 imu_integration::IntegrateAngularVelocities | ( | const std::vector< localization_measurements::ImuMeasurement > & | imu_measurements, | 
| const gtsam::Rot3 & | starting_orientation, | ||
| const localization_common::Time | starting_time | ||
| ) | 
| boost::optional< lm::ImuMeasurement > imu_integration::Interpolate | ( | const localization_measurements::ImuMeasurement & | imu_measurement_a, | 
| const localization_measurements::ImuMeasurement & | imu_measurement_b, | ||
| const localization_common::Time | timestamp | ||
| ) | 
| std::unique_ptr< Filter > imu_integration::LoadFilter | ( | const std::string & | filter_type | ) | 
| void imu_integration::LoadImuFilterParams | ( | config_reader::ConfigReader & | config, | 
| ImuFilterParams & | params | ||
| ) | 
| void imu_integration::LoadImuIntegratorParams | ( | config_reader::ConfigReader & | config, | 
| ImuIntegratorParams & | params | ||
| ) | 
| gtsam::PreintegratedCombinedMeasurements imu_integration::Pim | ( | const gtsam::imuBias::ConstantBias & | bias, | 
| const boost::shared_ptr< gtsam::PreintegratedCombinedMeasurements::Params > & | params | ||
| ) | 
| lc::CombinedNavState imu_integration::PimPredict | ( | const localization_common::CombinedNavState & | combined_nav_state, | 
| const gtsam::PreintegratedCombinedMeasurements & | pim | ||
| ) |