Filters#
The following filters handle synchronization, serialization timeout and other operations on streams.
-
template<AnyStream... Inputs>
static auto icey::any(Inputs... inputs)# Outputs the value or error of any of the inputs. All the inputs must have the same Value and Error type.
- Template Parameters:
Inputs – A list of Stream<Value, Error> types, i.e. all the input Streams must have the same Value and Error type.
- Returns:
Stream<Value, Error>
-
template<ErrorFreeStream... Inputs>
static ApproxTimeSynchronizer<MessageOf<Inputs>...> icey::synchronize_approx_time(uint32_t queue_size, Inputs... inputs)# Synchronize at least two streams by approximately matching the header time-stamps (using the
message_filters::Synchronizer
). It accepts only an ErrorFreeStream since the synchronizer may emit new errors. To obtain an ErrorFreeStream, use Stream::unwrap_or.- Template Parameters:
Inputs – the input stream types, not necessarily all the same
- Parameters:
queue_size – the queue size to use, 100 is a good value.
inputs – the input streams, not necessarily all of the same type
-
template<class Value>
struct Buffer : public icey::Stream<std::shared_ptr<std::vector<Value>>, Nothing, BufferImpl<Value>># This stream is created when calling Stream::buffer. A Buffer is a Stream that holds an array of values. It accumulates a certain amount of values and only then it has itself a value. It does not have errors since it does not make much sense to accumulate errors.
See also
-
template<class ...Messages>
class ApproxTimeSynchronizer : public icey::Stream<std::tuple<Messages::SharedPtr...>, std::string, ApproxTimeSynchronizerImpl<Messages...>># A Stream representing an approximate time synchronizer from the message_filters package.
See also
synchronize_approx_time
-
template<class Value>
struct TransformSynchronizer : public icey::Stream<std::tuple<Value, geometry_msgs::msg::TransformStamped>, std::string, TransformSynchronizerImpl<remove_shared_ptr_t<Value>>># Synchronizes a topic with a transform using tf2_ros::MessageFilter.
Public Types
Public Functions
-
template<ErrorFreeStream Input = Stream<int>>
TransformSynchronizer(Context &context, const std::string &target_frame, const Duration &lookup_timeout, Input *input = nullptr)# Construct the TransformSynchronizer and connect it to the input.
- Parameters:
target_frame – the transform on which we wait is specified by source_frame and target_frame, where source_frame is the frame in the header of the message
lookup_timeout – The maximum time to wait until the transform gets available for a message
-
template<ErrorFreeStream Input = Stream<int>>
-
template<class Value>
struct TimeoutFilter : public icey::Stream<Value, std::tuple<rclcpp::Time, rclcpp::Time, rclcpp::Duration>># A filter that detects timeouts, i.e. whether a value was received in a given time window. It simply passes over the value if no timeout occurred, and errors otherwise.
- Template Parameters:
_Value – the value must be a message that has a header stamp
Public Functions
-
template<AnyStream Input>
TimeoutFilter(Context &context, Input input, const Duration &max_age, bool create_extra_timer = true)# Construct the filter an connect it to the input.
- Template Parameters:
Input – another Stream that holds as a value a ROS message with a header stamp
- Parameters:
node – the node is needed to know the current time
input – another Stream which is the input to this filter
max_age – a maximum age the message is allowed to have.
create_extra_timer – If set to false, the timeout will only be detected after at least one message was received. If set to true, an extra timer is created so that timeouts can be detected even if no message is received
-
template<class Message>
struct SimpleFilterAdapter : public icey::Stream<Message::SharedPtr, Nothing, SimpleFilterAdapterImpl<Message>># Adapts the
message_filters::SimpleFilter
to ourStream
(which is a similar concept).Note
This is essentially the same as what
message_filters::Subscriber
does: ros2/message_filtersPublic Types
Public Functions
-
SimpleFilterAdapter(Context &context)#
Constructs a new instance and connects this Stream to the
message_filters::SimpleFilter
so thatsignalMessage
is called every time thisicey::Stream
receives a value.
-
SimpleFilterAdapter(Context &context)#