NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots 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 AddImuMeasurement (const localization_measurements::ImuMeasurement &imu_measurement)
 
boost::optional< gtsam::PreintegratedCombinedMeasurements > IntegratedPim (const gtsam::imuBias::ConstantBias &bias, const localization_common::Time start_time, const localization_common::Time end_time) const
 
boost::optional< localization_common::CombinedNavStateExtrapolate (const localization_common::CombinedNavState &combined_nav_state, const localization_common::Time end_time) const
 
boost::optional< localization_common::CombinedNavStateExtrapolateLatest (const localization_common::CombinedNavState &combined_nav_state) const
 
void SetFanSpeedMode (const localization_measurements::FanSpeedMode fan_speed_mode)
 
localization_measurements::FanSpeedMode fan_speed_mode () const
 
- Public Member Functions inherited from localization_common::TimestampedSet< localization_measurements::ImuMeasurement >
 TimestampedSet (const boost::optional< int > max_size=boost::none)
 
 TimestampedSet (const std::vector< Time > &timestamps, const std::vector< localization_measurements::ImuMeasurement > &values, const boost::optional< int > max_size=boost::none)
 
 ~TimestampedSet ()=default
 
bool Add (const Time timestamp, const localization_measurements::ImuMeasurement &value)
 
bool Remove (const Time timestamp)
 
boost::optional< TimestampedValue< localization_measurements::ImuMeasurement > > Get (const Time timestamp) const
 
size_t size () const
 
bool empty () const
 
void Clear ()
 
boost::optional< TimestampedValue< localization_measurements::ImuMeasurement > > Oldest () const
 
boost::optional< TimeOldestTimestamp () const
 
boost::optional< TimestampedValue< localization_measurements::ImuMeasurement > > Latest () const
 
boost::optional< TimeLatestTimestamp () const
 
bool WithinBounds (const Time timestamp) const
 
std::pair< boost::optional< TimestampedValue< localization_measurements::ImuMeasurement > >, boost::optional< TimestampedValue< localization_measurements::ImuMeasurement > > > LowerAndUpperBound (const Time timestamp) const
 
boost::optional< TimestampedValue< localization_measurements::ImuMeasurement > > Closest (const Time timestamp) const
 
boost::optional< TimestampedValue< localization_measurements::ImuMeasurement > > LowerBoundOrEqual (const Time timestamp) const
 
std::vector< TimeTimestamps () const
 
double Duration () const
 
bool Contains (const Time timestamp) const
 
std::vector< TimestampedValue< localization_measurements::ImuMeasurement > > LatestValues (const Time oldest_allowed_timestamp) const
 
std::vector< TimestampedValue< localization_measurements::ImuMeasurement > > OldValues (const Time oldest_allowed_timestamp) const
 
std::vector< TimestampedValue< localization_measurements::ImuMeasurement > > DownsampledValues (const TimestampSetType &allowed_timestamps) const
 
int RemoveOldValues (const Time oldest_allowed_timestamp)
 
int RemoveBelowLowerBoundValues (const Time timestamp)
 
boost::optional< TimestampedValue< localization_measurements::ImuMeasurement > > RemoveOldest ()
 
const std::map< Time, localization_measurements::ImuMeasurement > & set () const
 
std::map< Time, localization_measurements::ImuMeasurement > & set ()
 
std::map< Time, localization_measurements::ImuMeasurement >::const_iterator cend () const
 
std::pair< typename std::map< Time, localization_measurements::ImuMeasurement >::const_iterator, typename std::map< Time, localization_measurements::ImuMeasurement >::const_iterator > InRangeValues (const Time oldest_allowed_timestamp, const Time latest_allowed_timestamp)
 

Constructor & Destructor Documentation

◆ ImuIntegrator()

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

Member Function Documentation

◆ AddImuMeasurement()

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

◆ Extrapolate()

boost::optional< lc::CombinedNavState > imu_integration::ImuIntegrator::Extrapolate ( const localization_common::CombinedNavState combined_nav_state,
const localization_common::Time  end_time 
) const

◆ ExtrapolateLatest()

boost::optional< localization_common::CombinedNavState > imu_integration::ImuIntegrator::ExtrapolateLatest ( const localization_common::CombinedNavState combined_nav_state) 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 
) const

◆ SetFanSpeedMode()

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

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