NASA Astrobee Robot Software  0.16.7
Flight software for the Astrobee robot operating inside the International Space Station.
imu_integration::ImuIntegrator Class Reference

#include <imu_integrator.h>

Inheritance diagram for imu_integration::ImuIntegrator:
Inheritance graph

Public Member Functions

 ImuIntegrator (const ImuIntegratorParams &params=ImuIntegratorParams())
 
void BufferImuMeasurement (const localization_measurements::ImuMeasurement &imu_measurement)
 
boost::optional< localization_common::TimeIntegrateImuMeasurements (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::TimeOldestTime () const
 
boost::optional< localization_common::TimeLatestTime () const
 
boost::optional< localization_measurements::ImuMeasurementLatestMeasurement () 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
 

Constructor & Destructor Documentation

◆ ImuIntegrator()

imu_integration::ImuIntegrator::ImuIntegrator ( const ImuIntegratorParams params = ImuIntegratorParams())
explicit

Member Function Documentation

◆ BufferImuMeasurement()

void imu_integration::ImuIntegrator::BufferImuMeasurement ( const localization_measurements::ImuMeasurement imu_measurement)

◆ Empty()

bool imu_integration::ImuIntegrator::Empty ( ) const

◆ fan_speed_mode()

lm::FanSpeedMode imu_integration::ImuIntegrator::fan_speed_mode ( ) const

◆ IntegratedPim()

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

◆ IntegrateImuMeasurements()

boost::optional< lc::Time > imu_integration::ImuIntegrator::IntegrateImuMeasurements ( const localization_common::Time  start_time,
const localization_common::Time  end_time,
gtsam::PreintegratedCombinedMeasurements &  pim 
) const

◆ LatestMeasurement()

boost::optional< lm::ImuMeasurement > imu_integration::ImuIntegrator::LatestMeasurement ( ) const

◆ LatestTime()

boost::optional< lc::Time > imu_integration::ImuIntegrator::LatestTime ( ) const

◆ measurements()

const std::map< localization_common::Time, localization_measurements::ImuMeasurement > & imu_integration::ImuIntegrator::measurements ( ) const

◆ OldestTime()

boost::optional< lc::Time > imu_integration::ImuIntegrator::OldestTime ( ) const

◆ pim_params()

boost::shared_ptr< gtsam::PreintegratedCombinedMeasurements::Params > imu_integration::ImuIntegrator::pim_params ( ) const

◆ RemoveOldMeasurements()

void imu_integration::ImuIntegrator::RemoveOldMeasurements ( const localization_common::Time  new_start_time)

◆ SetFanSpeedMode()

void imu_integration::ImuIntegrator::SetFanSpeedMode ( const localization_measurements::FanSpeedMode  fan_speed_mode)

◆ Size()

int imu_integration::ImuIntegrator::Size ( ) const

◆ WithinBounds()

bool imu_integration::ImuIntegrator::WithinBounds ( const localization_common::Time  timestamp)

The documentation for this class was generated from the following files: