ROS2 message filter approximate time policy callback doesn't run
I am trying to sync two message streams of 2 image topics. So I am using message filters. I was using a class to do all this, however, the callback doesnt seem to be running. I have echoed the rostopics in the terminal and they seem to be outputting the messages. What could be happening here?
What is allowed time delay in the approximate policy in receiving the two topic streams(I atleast have topics matching every second right now)?
I guess I may be doing something wrong there. (Things do work if i create two different subscribers with their own callbacks)
This is my code-
class MultiSubscriber : public rclcpp::Node
{
public:
message_filters::Subscriber<sensor_msgs::msg::Image> image_sub_;
message_filters::Subscriber<sensor_msgs::msg::Image> disparity_sub_;
MultiSubscriber(const std::string& name)
: Node(name)
{
image_sub_.subscribe(this, "/image_color");
disparity_sub_.subscribe(this, "/image_disparity");
typedef message_filters::sync_policies::ApproximateTime<sensor_msgs::msg::Image, sensor_msgs::msg::Image> approximate_policy;
message_filters::Synchronizer<approximate_policy>syncApproximate(approximate_policy(10), image_sub_, disparity_sub_);
syncApproximate.setMaxIntervalDuration(rclcpp::Duration(3,0)); // Added after a comment
syncApproximate.registerCallback(&MultiSubscriber::disparityCb,this);
}
private:
void disparityCb(const sensor_msgs::msg::Image::SharedPtr disparity_msg, const sensor_msgs::msg::Image::SharedPtr color_msg)
{
std::cout<<"Hello messages are being received";
}};
Just to add to this. This is the output of -
ros2 node info /obstacle_detection
/obstacle_detection
Subscribers:
/image_disparity: sensor_msgs/msg/Image
/image_color: sensor_msgs/msg/Image
/parameter_events: rcl_interfaces/msg/ParameterEvent
Publishers:
/parameter_events: rcl_interfaces/msg/ParameterEvent
/rosout: rcl_interfaces/msg/Log
Service Servers:
/obstacle_detection/describe_parameters: rcl_interfaces/srv/DescribeParameters
/obstacle_detection/get_parameter_types: rcl_interfaces/srv/GetParameterTypes
/obstacle_detection/get_parameters: rcl_interfaces/srv/GetParameters
/obstacle_detection/list_parameters: rcl_interfaces/srv/ListParameters
/obstacle_detection/set_parameters: rcl_interfaces/srv/SetParameters
/obstacle_detection/set_parameters_atomically: rcl_interfaces/srv/SetParametersAtomically
Service Clients:
Action Servers:
Action Clients:
Edit-
Error Message on changing the registerCallback call to syncApproximate.registerCallback(std::bind (&MultiSubscriber::disparityCb, this,_1,_2));
Edit 2- This github issue shows how the registercallback is to be called.
I am assuming that the headers for each image message has been populated correctly. Try outputting the stamps
msg->header.stamp.sec
andmsg->header.stamp.nsec
from each message to debug if the times are syncing.Also try using
ros2 topic info <TOPIC>
for each topic, and confirm that you observe expected values forPublisher count
andSubscriber count
.