![]() |
NASA Astrobee Robot Software
0.16.7
Flight software for the Astrobee robot operating inside the International Space Station.
|
#include <imu_integrator.h>
Public Member Functions | |
ImuIntegrator (const ImuIntegratorParams ¶ms=ImuIntegratorParams()) | |
void | BufferImuMeasurement (const localization_measurements::ImuMeasurement &imu_measurement) |
boost::optional< localization_common::Time > | IntegrateImuMeasurements (const localization_common::Time start_time, const localization_common::Time end_time, gtsam::PreintegratedCombinedMeasurements &pim) const |
boost::optional< gtsam::PreintegratedCombinedMeasurements > | IntegratedPim (const gtsam::imuBias::ConstantBias &bias, const localization_common::Time start_time, const localization_common::Time end_time, boost::shared_ptr< gtsam::PreintegratedCombinedMeasurements::Params > params) const |
void | RemoveOldMeasurements (const localization_common::Time new_start_time) |
boost::optional< localization_common::Time > | OldestTime () const |
boost::optional< localization_common::Time > | LatestTime () const |
boost::optional< localization_measurements::ImuMeasurement > | LatestMeasurement () const |
bool | Empty () const |
int | Size () const |
void | SetFanSpeedMode (const localization_measurements::FanSpeedMode fan_speed_mode) |
localization_measurements::FanSpeedMode | fan_speed_mode () const |
boost::shared_ptr< gtsam::PreintegratedCombinedMeasurements::Params > | pim_params () const |
bool | WithinBounds (const localization_common::Time timestamp) |
const std::map< localization_common::Time, localization_measurements::ImuMeasurement > & | measurements () const |
|
explicit |
void imu_integration::ImuIntegrator::BufferImuMeasurement | ( | const localization_measurements::ImuMeasurement & | imu_measurement | ) |
bool imu_integration::ImuIntegrator::Empty | ( | ) | const |
lm::FanSpeedMode imu_integration::ImuIntegrator::fan_speed_mode | ( | ) | const |
boost::optional< gtsam::PreintegratedCombinedMeasurements > imu_integration::ImuIntegrator::IntegratedPim | ( | const gtsam::imuBias::ConstantBias & | bias, |
const localization_common::Time | start_time, | ||
const localization_common::Time | end_time, | ||
boost::shared_ptr< gtsam::PreintegratedCombinedMeasurements::Params > | params | ||
) | const |
boost::optional< lc::Time > imu_integration::ImuIntegrator::IntegrateImuMeasurements | ( | const localization_common::Time | start_time, |
const localization_common::Time | end_time, | ||
gtsam::PreintegratedCombinedMeasurements & | pim | ||
) | const |
boost::optional< lm::ImuMeasurement > imu_integration::ImuIntegrator::LatestMeasurement | ( | ) | const |
boost::optional< lc::Time > imu_integration::ImuIntegrator::LatestTime | ( | ) | const |
const std::map< localization_common::Time, localization_measurements::ImuMeasurement > & imu_integration::ImuIntegrator::measurements | ( | ) | const |
boost::optional< lc::Time > imu_integration::ImuIntegrator::OldestTime | ( | ) | const |
boost::shared_ptr< gtsam::PreintegratedCombinedMeasurements::Params > imu_integration::ImuIntegrator::pim_params | ( | ) | const |
void imu_integration::ImuIntegrator::RemoveOldMeasurements | ( | const localization_common::Time | new_start_time | ) |
void imu_integration::ImuIntegrator::SetFanSpeedMode | ( | const localization_measurements::FanSpeedMode | fan_speed_mode | ) |
int imu_integration::ImuIntegrator::Size | ( | ) | const |
bool imu_integration::ImuIntegrator::WithinBounds | ( | const localization_common::Time | timestamp | ) |