ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
What follows is a correct version of the code:
#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);
sync.reset(new Sync(MySyncPolicy(10), sub1, sub2));
sync->registerCallback(boost::bind(&Node::callback, this, _1, _2));
}
void callback(const control_sys::IntWithHeaderConstPtr &in1, const control_sys::IntWithHeaderConstPtr &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;
typedef Synchronizer<MySyncPolicy> Sync;
boost::shared_ptr<Sync> sync;
};
int main(int argc, char **argv)
{
ros::init(argc, argv, "synchronizer");
Node synchronizer;
ros::spin();
}