FKIE Message Filters
Improved filters for processing ROS messages
|
Approximate time policy. More...
#include <fkie_message_filters/combiner_policies/approximate_time.h>
Public Types | |
using | EmitterCB = std::function< void(const OutgoingTuple &)> |
Callback for assembled outputs. | |
using | IncomingTuples = std::tuple< helpers::io_tuple_t< IOs >... > |
Tuple type of incoming data tuples. | |
using | OutgoingTuple = helpers::io_tuple_t< helpers::io_concat_t< IOs... > > |
Combined tuple type for data output. | |
Public Member Functions | |
ApproximateTime () | |
Constructor. More... | |
ApproximateTime & | set_max_age (const ros::Duration &max_age) noexcept |
Set maximum age of any data in the queue. More... | |
ApproximateTime & | set_max_queue_size (std::size_t queue_size, const boost::optional< ros::Duration > &max_age=boost::none) noexcept |
Set maximum queue size. More... | |
ApproximateTime & | set_max_timespan (const ros::Duration &max_delta) noexcept |
Set maximum permissible timestamp difference of matched messages. More... | |
ApproximateTime & | set_min_distance (std::size_t i, const ros::Duration &min_dist) noexcept |
Set the minimum distance between consecutive messages on a source. More... | |
Protected Types | |
using | MaybeOutgoingTuples = std::tuple< boost::optional< helpers::io_tuple_t< IOs > >... > |
Tuple of outgoing tuple candidates. More... | |
Protected Member Functions | |
template<std::size_t N> | |
void | add (std::unique_lock< std::mutex > &, const std::tuple_element_t< N, IncomingTuples > &) |
Input function. More... | |
void | emit (const OutgoingTuple &out) |
Emit data. More... | |
void | reset () noexcept override |
Reset internal state. More... | |
void | set_emitter_callback (const EmitterCB &) noexcept |
Set output function. More... | |
Approximate time policy.
This is a policy for the Combiner class. It will associate data from the connected sources, but unlike ExactTime, it can match messages even when their ROS header timestamps do not match perfectly. If an input source is not unary, only the first argument will be examined to determine the timestamp. It must have an accessible ROS header, which is determined using the ros::message_traits
template.
The policy employs a modified version of the ROS ApproximateTime algorithm. Like its predecessor, the algorithm is not merely applying an epsilon to account for time differences, but tries to find the best possible match. Each set of grouped messages which are output by the policy, satisfies the following criteria:
Optional parameters:
The algorithm works as follows:
|
protectedinherited |
Tuple of outgoing tuple candidates.
This is basically a tuple of optionals, so elements can remain empty until a suitable data element has been found by the policy.
fkie_message_filters::combiner_policies::ApproximateTime< IOs >::ApproximateTime | ( | ) |
Constructor.
|
protected |
Input function.
This function will be called by the Combiner class for incoming data.
|
protectedinherited |
Emit data.
This returns combined data back to the Combiner class.
|
overrideprotectedvirtualnoexcept |
Reset internal state.
This function is called by the Combiner if the filter is reset.
Implements fkie_message_filters::combiner_policies::PolicyBase< IOs... >.
|
protectednoexceptinherited |
Set output function.
This function is called by the policy whenever it has output ready to be passed on.
|
noexcept |
Set maximum age of any data in the queue.
This is equivalent to
max_age
maximum age
|
noexcept |
Set maximum queue size.
queue_size
maximum queue size per slot (zero means unlimited) max_age
the maximum age of any data in the queue (none
means unlimited)
|
noexcept |
Set maximum permissible timestamp difference of matched messages.
max_delta
the maximum permissible timestamp difference of matched messages
|
noexcept |
Set the minimum distance between consecutive messages on a source.
If it is known in advance that messages from a certain source cannot arrive closer together than min_dist, the policy can conclude earlier that a set of matched messages is optimal, thereby reducing the introduced lag. A typical example would be a camera with fixed frame rate F, where the minimum distance between consecutive messages can be assumed to be at least 0.5/F
.
i
the input source slot min_dist
the minimum temporal distance between consecutive messages