ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
You have to use the message_filter
package.
Among the other things, this allows you to create synchronized callbacks.
You can use it to define callbacks which takes more than 1 message as argument.
Note that all messages must have an header
field with the timestamp.
void sync_callback(const StampedStringMsg::SharedPtr string_msg, const StampedBooleanMsg::SharedPtr bool_msg)
{
std::cout<<"Received msg: "<< string_msg->data<< " and msg " << bool_msg->data<<std::endl;
}
You need to choose a synchronization strategy: exact or approximate. The first one will require that both messages have the exact same timestamp in order for the callback to be triggered. The other will use heuristics to try to match messages with slightly different timestamps.
// create subscribers to the topics of interest
message_filters::Subscriber<StampedStringMsg> string_sub(g_node, "stamped_string_topic", custom_qos_profile);
message_filters::Subscriber<StampedBooleanMsg> bool_sub(g_node, "stamped_boolean_topic", custom_qos_profile);
// exact time policy
typedef message_filters::sync_policies::ExactTime<StampedStringMsg, StampedBooleanMsg> exact_policy;
message_filters::Synchronizer<exact_policy>syncExact(exact_policy(10), string_sub, bool_sub);
// register the exact time callback
syncExact.registerCallback(exact_sync_callback);
You can find a full working example here https://github.com/alsora/ros2-code-examples#time-synchronization-message-filters
2 | No.2 Revision |
You have to use the message_filter
package.
Among the other things, this allows you to create synchronized callbacks.
You can use it to define callbacks which takes more than 1 message as argument.
Note that all messages must have an header
field with the timestamp.
void sync_callback(const StampedStringMsg::SharedPtr string_msg, const StampedBooleanMsg::SharedPtr bool_msg)
{
std::cout<<"Received msg: "<< string_msg->data<< " and msg " << bool_msg->data<<std::endl;
}
You need to choose a synchronization strategy: exact or approximate. The first one will require that both messages have the exact same timestamp in order for the callback to be triggered. The other will use heuristics to try to match messages with slightly different timestamps.
// create subscribers to the topics of interest
message_filters::Subscriber<StampedStringMsg> string_sub(g_node, "stamped_string_topic", custom_qos_profile);
message_filters::Subscriber<StampedBooleanMsg> bool_sub(g_node, "stamped_boolean_topic", custom_qos_profile);
// exact time policy
typedef message_filters::sync_policies::ExactTime<StampedStringMsg, StampedBooleanMsg> exact_policy;
message_filters::Synchronizer<exact_policy>syncExact(exact_policy(10), string_sub, bool_sub);
// register the exact time callback
syncExact.registerCallback(exact_sync_callback);
syncExact.registerCallback(sync_callback);
You can find a full working example here https://github.com/alsora/ros2-code-examples#time-synchronization-message-filters
3 | No.3 Revision |
You have to use the message_filter
package.
Among the other things, this allows you to create synchronized callbacks.
You can use it to define callbacks which takes more than 1 message as argument.
Note that all messages must have an header
field with the timestamp.
void sync_callback(const StampedStringMsg::SharedPtr string_msg, const StampedBooleanMsg::SharedPtr bool_msg)
{
std::cout<<"Received msg: "<< string_msg->data<< " and msg " << bool_msg->data<<std::endl;
}
You need to choose a synchronization strategy: exact or approximate. The first one will require that both messages have the exact same timestamp in order for the callback to be triggered. The other will use heuristics to try to match messages with slightly different timestamps.
// create subscribers to the topics of interest
message_filters::Subscriber<StampedStringMsg> string_sub(g_node, string_sub(node, "stamped_string_topic", custom_qos_profile);
qos_profile);
message_filters::Subscriber<StampedBooleanMsg> bool_sub(g_node, bool_sub(node, "stamped_boolean_topic", custom_qos_profile);
qos_profile);
// exact time policy
typedef message_filters::sync_policies::ExactTime<StampedStringMsg, StampedBooleanMsg> exact_policy;
message_filters::Synchronizer<exact_policy>syncExact(exact_policy(10), string_sub, bool_sub);
// register the exact time callback
syncExact.registerCallback(sync_callback);
You can find a full working example here https://github.com/alsora/ros2-code-examples#time-synchronization-message-filters