Template Struct LatestTime

Nested Relationships

Nested Types

Inheritance Relationships

Base Type

  • public message_filters::PolicyBase< M0, M1, NullType, NullType, NullType, NullType, NullType, NullType, NullType > (Template Struct PolicyBase)

Struct Documentation

template<typename M0, typename M1, typename M2 = NullType, typename M3 = NullType, typename M4 = NullType, typename M5 = NullType, typename M6 = NullType, typename M7 = NullType, typename M8 = NullType>
struct LatestTime : public message_filters::PolicyBase<M0, M1, NullType, NullType, NullType, NullType, NullType, NullType, NullType>

Public Types

typedef Synchronizer<LatestTime> Sync
typedef PolicyBase<M0, M1, M2, M3, M4, M5, M6, M7, M8> Super
typedef Super::Messages Messages
typedef Super::Signal Signal
typedef Super::Events Events
typedef Super::RealTypeCount RealTypeCount
typedef std::tuple<double, double, double> RateConfig

filter coeffs and error margin factor: <rate_ema_alpha, error_ema_alpha, rate_step_change_margin_factor>

Public Functions

inline LatestTime()
inline LatestTime(rclcpp::Clock::SharedPtr clock)
inline LatestTime(const LatestTime &e)
inline LatestTime &operator=(const LatestTime &rhs)
inline void initParent(Sync *parent)
inline void setRateConfigPerMessage(const std::vector<RateConfig> &configs)
inline void setRateConfig(const RateConfig &config)
inline void setClock(rclcpp::Clock::SharedPtr clock)
template<int i>
inline void add(const typename std::tuple_element<i, Events>::type &evt)