Template Struct ApproximateTime

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 ApproximateTime : public message_filters::PolicyBase<M0, M1, NullType, NullType, NullType, NullType, NullType, NullType, NullType>

Public Types

typedef Synchronizer<ApproximateTime> 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 Super::M0Event M0Event
typedef Super::M1Event M1Event
typedef Super::M2Event M2Event
typedef Super::M3Event M3Event
typedef Super::M4Event M4Event
typedef Super::M5Event M5Event
typedef Super::M6Event M6Event
typedef Super::M7Event M7Event
typedef Super::M8Event M8Event
typedef std::deque<M0Event> M0Deque
typedef std::deque<M1Event> M1Deque
typedef std::deque<M2Event> M2Deque
typedef std::deque<M3Event> M3Deque
typedef std::deque<M4Event> M4Deque
typedef std::deque<M5Event> M5Deque
typedef std::deque<M6Event> M6Deque
typedef std::deque<M7Event> M7Deque
typedef std::deque<M8Event> M8Deque
typedef std::vector<M0Event> M0Vector
typedef std::vector<M1Event> M1Vector
typedef std::vector<M2Event> M2Vector
typedef std::vector<M3Event> M3Vector
typedef std::vector<M4Event> M4Vector
typedef std::vector<M5Event> M5Vector
typedef std::vector<M6Event> M6Vector
typedef std::vector<M7Event> M7Vector
typedef std::vector<M8Event> M8Vector
typedef Events Tuple
typedef std::tuple<M0Deque, M1Deque, M2Deque, M3Deque, M4Deque, M5Deque, M6Deque, M7Deque, M8Deque> DequeTuple
typedef std::tuple<M0Vector, M1Vector, M2Vector, M3Vector, M4Vector, M5Vector, M6Vector, M7Vector, M8Vector> VectorTuple

Public Functions

inline ApproximateTime(uint32_t queue_size)
inline ApproximateTime(const ApproximateTime &e)
inline ApproximateTime &operator=(const ApproximateTime &rhs)
inline void initParent(Sync *parent)
template<int i>
inline void checkInterMessageBound()
template<int i>
inline void add(const typename std::tuple_element<i, Events>::type &evt)
inline void setAgePenalty(double age_penalty)
inline void setInterMessageLowerBound(int i, rclcpp::Duration lower_bound)
inline void setMaxIntervalDuration(rclcpp::Duration max_interval_duration)