Synchronizer with approximate time policy in a class [C++]
I have been trying to implement a synchronizer with approximate time policy in a class. The following code compiles with no problem. But how should I define the Synchronizer
and the registerCallback
? (The two commented lines)
#include "header.h"
using namespace message_filters;
typedef control_sys::IntWithHeader myMsg;
class Node
{
public:
Node()
{
sub1.subscribe(node, "in1", 1);
sub2.subscribe(node, "in2", 1);
}
void callback(const myMsg &in1, const myMsg &in2)
{
std::cout << "Synchronization successful" << std::endl;
}
private:
ros::NodeHandle node;
ros::Publisher pub;
std_msgs::Int32 out;
message_filters::Subscriber<myMsg> sub1;
message_filters::Subscriber<myMsg> sub2;
typedef sync_policies::ApproximateTime<myMsg, myMsg> MySyncPolicy;
// This is how I would define them inside main()
//Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), sub1, sub2);
//sync.registerCallback(&callback);
};
int main(int argc, char **argv)
{
ros::init(argc, argv, "synchronizer");
Node synchronizer;
ros::spin();
}
Update 1: Headers included:
#include <ros/ros.h>
#include <std_msgs/Int32.h>
#include <iostream>
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include "control_sys/IntWithHeader.h"
Update 2: Error output of catkin_make
(in terminal)
What are the includes in
header.h
?One of the errors is
/usr/include/boost/bind/mem_fn_template.hpp:299:7: note: no known conversion for argument 1 from ‘Node*’ to ‘Node&’
. Can you put an update showing the file as you have it now? That looks suspicious, like a copy-paste error from one of us.I am wondering if your final code is working. I have been trying to implement a similar class as yours but my callback function is never called.
I haven't run this for a while, but I remember that it was working fine. Have a look.