NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
localization_common::TimestampedInterpolater< T, ParamsT > Class Template Reference

#include <timestamped_interpolater.h>

Inheritance diagram for localization_common::TimestampedInterpolater< T, ParamsT >:
Inheritance graph

Public Member Functions

 TimestampedInterpolater (const boost::optional< int > max_size=boost::none)
 
 TimestampedInterpolater (const std::vector< Time > &timestamps, const std::vector< T > &objects, const boost::optional< int > max_size=boost::none)
 
boost::optional< T > Interpolate (const Time timestamp) const
 
Interpolate (const T &a, const T &b, const double alpha) const
 
boost::optional< T > Relative (const Time timestamp_a, const Time timestamp_b) const
 
Relative (const T &a, const T &b) const
 
ParamsT & params ()
 
const ParamsT & params () const
 
- Public Member Functions inherited from localization_common::TimestampedSet< T >
 TimestampedSet (const boost::optional< int > max_size=boost::none)
 
 ~TimestampedSet ()=default
 
 TimestampedSet (const std::vector< Time > &timestamps, const std::vector< T > &values, const boost::optional< int > max_size=boost::none)
 
bool Add (const Time timestamp, const T &value)
 
bool Remove (const Time timestamp)
 
boost::optional< TimestampedValue< T > > Get (const Time timestamp) const
 
size_t size () const
 
bool empty () const
 
void Clear ()
 
boost::optional< TimestampedValue< T > > Oldest () const
 
boost::optional< TimeOldestTimestamp () const
 
boost::optional< TimestampedValue< T > > Latest () const
 
boost::optional< TimeLatestTimestamp () const
 
bool WithinBounds (const Time timestamp) const
 
std::pair< boost::optional< TimestampedValue< T > >, boost::optional< TimestampedValue< T > > > LowerAndUpperBound (const Time timestamp) const
 
boost::optional< TimestampedValue< T > > Closest (const Time timestamp) const
 
boost::optional< TimestampedValue< T > > LowerBoundOrEqual (const Time timestamp) const
 
std::vector< TimeTimestamps () const
 
double Duration () const
 
bool Contains (const Time timestamp) const
 
std::vector< TimestampedValue< T > > LatestValues (const Time oldest_allowed_timestamp) const
 
std::vector< TimestampedValue< T > > OldValues (const Time oldest_allowed_timestamp) const
 
template<typename TimestampSetType >
std::vector< TimestampedValue< T > > DownsampledValues (const TimestampSetType &allowed_timestamps) const
 
int RemoveOldValues (const Time oldest_allowed_timestamp)
 
int RemoveBelowLowerBoundValues (const Time timestamp)
 
boost::optional< TimestampedValue< T > > RemoveOldest ()
 
const std::map< Time, T > & set () const
 
std::map< Time, T > & set ()
 
std::map< Time, T >::const_iterator cend () const
 
std::pair< typename std::map< Time, T >::const_iterator, typename std::map< Time, T >::const_iterator > InRangeValues (const Time oldest_allowed_timestamp, const Time latest_allowed_timestamp)
 

Public Attributes

boost::optional< gtsam::Matrix > covariance_a_b
 

Constructor & Destructor Documentation

◆ TimestampedInterpolater() [1/2]

template<typename T , class ParamsT >
localization_common::TimestampedInterpolater< T, ParamsT >::TimestampedInterpolater ( const boost::optional< int >  max_size = boost::none)
explicit

◆ TimestampedInterpolater() [2/2]

template<typename T , class ParamsT >
localization_common::TimestampedInterpolater< T, ParamsT >::TimestampedInterpolater ( const std::vector< Time > &  timestamps,
const std::vector< T > &  objects,
const boost::optional< int >  max_size = boost::none 
)

Member Function Documentation

◆ Interpolate() [1/2]

template<typename T , class ParamsT >
T localization_common::TimestampedInterpolater< T, ParamsT >::Interpolate ( const T &  a,
const T &  b,
const double  alpha 
) const

◆ Interpolate() [2/2]

template<typename T , class ParamsT >
boost::optional< T > localization_common::TimestampedInterpolater< T, ParamsT >::Interpolate ( const Time  timestamp) const

◆ params() [1/2]

template<typename T , class ParamsT >
const ParamsT & localization_common::TimestampedInterpolater< T, ParamsT >::params

◆ params() [2/2]

template<typename T , class ParamsT = DefaultInterpolationParams>
const ParamsT& localization_common::TimestampedInterpolater< T, ParamsT >::params ( ) const

◆ Relative() [1/2]

template<typename T , class ParamsT >
T localization_common::TimestampedInterpolater< T, ParamsT >::Relative ( const T &  a,
const T &  b 
) const

◆ Relative() [2/2]

boost::optional< PoseWithCovariance > localization_common::PoseWithCovarianceInterpolater::Relative ( const Time  timestamp_a,
const Time  timestamp_b 
) const

Member Data Documentation

◆ covariance_a_b

template<typename T , class ParamsT = DefaultInterpolationParams>
boost::optional<gtsam::Matrix> localization_common::TimestampedInterpolater< T, ParamsT >::covariance_a_b
mutable

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