![]() |
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
#include <timestamped_set.h>

Public Member Functions | |
| TimestampedSet (const boost::optional< int > max_size=boost::none) | |
| ~TimestampedSet ()=default | |
| TimestampedSet (const std::vector< Time > ×tamps, 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< Time > | OldestTimestamp () const |
| boost::optional< TimestampedValue< T > > | Latest () const |
| boost::optional< Time > | LatestTimestamp () 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< Time > | Timestamps () 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) |
Friends | |
| class | boost::serialization::access |
|
explicit |
|
default |
| localization_common::TimestampedSet< T >::TimestampedSet | ( | const std::vector< Time > & | timestamps, |
| const std::vector< T > & | values, | ||
| const boost::optional< int > | max_size = boost::none |
||
| ) |
| bool localization_common::TimestampedSet< T >::Add | ( | const Time | timestamp, |
| const T & | value | ||
| ) |
| std::map< Time, T >::const_iterator localization_common::TimestampedSet< T >::cend |
| void localization_common::TimestampedSet< T >::Clear |
| boost::optional< TimestampedValue< T > > localization_common::TimestampedSet< T >::Closest | ( | const Time | timestamp | ) | const |
| bool localization_common::TimestampedSet< T >::Contains | ( | const Time | timestamp | ) | const |
| std::vector< TimestampedValue< T > > localization_common::TimestampedSet< T >::DownsampledValues | ( | const TimestampSetType & | allowed_timestamps | ) | const |
| double localization_common::TimestampedSet< T >::Duration |
| bool localization_common::TimestampedSet< T >::empty |
| boost::optional< TimestampedValue< T > > localization_common::TimestampedSet< T >::Get | ( | const Time | timestamp | ) | const |
| std::pair< typename std::map< Time, T >::const_iterator, typename std::map< Time, T >::const_iterator > localization_common::TimestampedSet< T >::InRangeValues | ( | const Time | oldest_allowed_timestamp, |
| const Time | latest_allowed_timestamp | ||
| ) |
| boost::optional< TimestampedValue< T > > localization_common::TimestampedSet< T >::Latest |
| boost::optional< Time > localization_common::TimestampedSet< T >::LatestTimestamp |
| std::vector< TimestampedValue< T > > localization_common::TimestampedSet< T >::LatestValues | ( | const Time | oldest_allowed_timestamp | ) | const |
| std::pair< boost::optional< TimestampedValue< T > >, boost::optional< TimestampedValue< T > > > localization_common::TimestampedSet< T >::LowerAndUpperBound | ( | const Time | timestamp | ) | const |
| boost::optional< TimestampedValue< T > > localization_common::TimestampedSet< T >::LowerBoundOrEqual | ( | const Time | timestamp | ) | const |
| boost::optional< TimestampedValue< T > > localization_common::TimestampedSet< T >::Oldest |
| boost::optional< Time > localization_common::TimestampedSet< T >::OldestTimestamp |
| std::vector< TimestampedValue< T > > localization_common::TimestampedSet< T >::OldValues | ( | const Time | oldest_allowed_timestamp | ) | const |
| bool localization_common::TimestampedSet< T >::Remove | ( | const Time | timestamp | ) |
| int localization_common::TimestampedSet< T >::RemoveBelowLowerBoundValues | ( | const Time | timestamp | ) |
| boost::optional< TimestampedValue< T > > localization_common::TimestampedSet< T >::RemoveOldest |
| int localization_common::TimestampedSet< T >::RemoveOldValues | ( | const Time | oldest_allowed_timestamp | ) |
| std::map<Time, T>& localization_common::TimestampedSet< T >::set | ( | ) |
| std::map< Time, T > & localization_common::TimestampedSet< T >::set |
| size_t localization_common::TimestampedSet< T >::size |
| std::vector< Time > localization_common::TimestampedSet< T >::Timestamps |
| bool localization_common::TimestampedSet< T >::WithinBounds | ( | const Time | timestamp | ) | const |
|
friend |