Template Class MessageBuffer

Class Documentation

template<typename Message>
class MessageBuffer

A utility class that maintains a history of received messages, and allows a range of messages to be easily queried by timestamp.

For motion models that rely on integrating multiple measurements together to form the requested constraint, this message buffer allows the received messages within a given time range to be easily extracted. It is then a matter of processing the messages to form the constraint.

It is assumed that all messages are received sequentially.

Public Types

using message_range = boost::any_range<const std::pair<rclcpp::Time, Message>, boost::forward_traversal_tag>

A range of messages.

An object representing a range defined by two iterators. It has begin() and end() methods (which means it can be used in range-based for loops), an empty() method, and a front() method for directly accessing the first member. When dereferenced, an iterator returns a std::pair<rclcpp::Time, MESSAGE>&.

using stamp_range = boost::any_range<const rclcpp::Time, boost::forward_traversal_tag>

A range of timestamps.

An object representing a range defined by two iterators. It has begin() and end() methods (which means it can be used in range-based for loops), an empty() method, and a front() method for directly accessing the first member. When dereferenced, an iterator returns a const rclcpp::Time&.

Public Functions

explicit MessageBuffer(const rclcpp::Duration &buffer_length = rclcpp::Duration::max())

Constructor

Parameters:

buffer_length[in] The length of the message buffer history. If queries arrive involving timestamps that are older than the buffer length, an exception will be thrown.

virtual ~MessageBuffer() = default

Destructor.

inline const rclcpp::Duration &bufferLength() const

Read-only access to the buffer length.

inline void bufferLength(const rclcpp::Duration &buffer_length)

Write access to the buffer length.

void insert(const rclcpp::Time &stamp, const Message &msg)

Insert a message to the buffer, using the provided timestamp.

The provided timestamp is assigned to the message and used to sort the messages in the buffer.

Parameters:
  • stamp[in] The stamp to assign to the message

  • msg[in] A message

message_range query(const rclcpp::Time &beginning_stamp, const rclcpp::Time &ending_stamp, bool extended_range = true)

Query the buffer for the set of messages between two timestamps.

The “edge behavior” is controlled by the extended_range flag.

Parameters:
  • beginning_stamp[in] The beginning timestamp of the constraint. beginning_stamp must be less than or equal to ending_stamp.

  • ending_stamp[in] The ending timestamp of the constraint. ending_stamp must be greater than or or equal to beginning_stamp.

  • extended_range[in] A flag indicating if the message range should be extended to include one message with a stamp less than or equal to the beginning_stamp and one message with a stamp greater than or equal to the ending_stamp. If false, the returned range only includes messages with stamps greater than beginning_stamp and less than ending_stamp.

Returns:

An iterator range containing all of the messages between the specified stamps.

stamp_range stamps() const

Read-only access to the current set of timestamps.

Returns:

An iterator range containing all known timestamps in ascending order

Protected Types

using Buffer = std::deque<std::pair<rclcpp::Time, Message>>

Protected Functions

void purgeHistory()

Remove any motion model segments that are older than buffer_length_.

The span of the buffer will be at least the requested buffer length, but it may be longer depending on the specific stamps of received messages.

Protected Attributes

Buffer buffer_

The container of received messages, sorted by timestamp.

rclcpp::Duration buffer_length_

The length of the motion model history. Segments older than buffer_length_ will be removed from the motion model history

Protected Static Functions

static inline const rclcpp::Time &extractStamp(const typename Buffer::value_type &element)

Helper function used with boost::transform_iterators to convert the internal Buffer value type into a const rclcpp::Time& iterator compatible with stamp_range.