ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
1

Synchronizer with approximate time policy in a class [C++]

asked 2018-01-25 11:24:41 -0600

mohsen gravatar image

updated 2018-01-27 09:17:10 -0600

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)

edit retag flag offensive close merge delete

Comments

1

What are the includes in header.h?

Thomas D gravatar image Thomas D  ( 2018-01-25 20:28:01 -0600 )edit

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.

Thomas D gravatar image Thomas D  ( 2018-01-26 09:58:38 -0600 )edit
1

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.

Vince4396 gravatar image Vince4396  ( 2018-07-31 22:52:03 -0600 )edit

I haven't run this for a while, but I remember that it was working fine. Have a look.

mohsen gravatar image mohsen  ( 2018-08-02 08:05:50 -0600 )edit

2 Answers

Sort by » oldest newest most voted
4

answered 2018-01-25 13:46:40 -0600

Thomas D gravatar image

updated 2018-01-27 08:39:59 -0600

Change your commented out lines to:

typedef sync_policies::ApproximateTime<myMsg, myMsg> MySyncPolicy;
typedef Synchronizer<MySyncPolicy> Sync;
boost::shared_ptr<Sync> sync;

In your constructor initialize and register:

sync.reset(new Sync(MySyncPolicy(10), sub1, sub2));      
sync->registerCallback(boost::bind(&Node::callback, this, _1, _2));

Update

A couple of other things to keep in mind.

  1. The messages you are subscribing to require a std_msgs/Header field so that message times can be compared.
  2. Change the signature of your callback to void callback(const control_sys::IntWithHeaderConstPtr &in1, const control_sys::IntWithHeaderConstPtr &in2).

With those types of changes I was able to get a node to compile that basically mimics what you have. I had to substitue myMsg for sensor_msgs/Image in order to use a message type I have access to.

edit flag offensive delete link more

Comments

sync->registerCallback(boost::bind(&Node::callback, this, _1, _2));

The line above causes a wall of error when I compile the package. It's too long to paste but I hope this helps.

error: no match for call to ‘(boost::_mfi::mf2<void, Node,
mohsen gravatar image mohsen  ( 2018-01-25 14:24:11 -0600 )edit

That is probably because you have not declared your callback function. After the parts that were commented out try void callback(const myMsg &in1, const myMsg &in2);

Thomas D gravatar image Thomas D  ( 2018-01-25 14:49:42 -0600 )edit

It still gives the same error (boost) + new errors caused by (I think) illegal function overload.

 error: ‘void Node::callback(const myMsg&, const myMsg&)’ cannot be overloaded  

 error: with ‘void Node::callback(const myMsg&, const myMsg&)’
mohsen gravatar image mohsen  ( 2018-01-25 15:47:40 -0600 )edit

Try making the function definition private.

Thomas D gravatar image Thomas D  ( 2018-01-25 19:33:33 -0600 )edit

Looking at it more, I think I was wrong about needing the extra function declaration in the code as you have it. Sorry about that.

Thomas D gravatar image Thomas D  ( 2018-01-25 19:40:42 -0600 )edit

That's alright. This is pretty advanced C++ for me so I really appreciate your help. Making the definition private didn't make a difference.

mohsen gravatar image mohsen  ( 2018-01-26 02:08:27 -0600 )edit

I have a gist of the entire package that builds for me at https://gist.github.com/tdenewiler/e2... .

Thomas D gravatar image Thomas D  ( 2018-01-26 19:24:58 -0600 )edit

Thanks for the update. But myMsgConstPtr is not a valid type so instead I changed the callback to

void callback(const control_sys::IntWithHeaderConstPtr &in1, const control_sys::IntWithHeaderConstPtr &in2)

and now it compiles and works properly. Would you mind editing your answer?

mohsen gravatar image mohsen  ( 2018-01-27 01:29:00 -0600 )edit
4

answered 2018-01-27 09:22:47 -0600

mohsen gravatar image

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();

}
edit flag offensive delete link more

Comments

Is this your solution or an update to your question?

jayess gravatar image jayess  ( 2018-01-27 19:04:50 -0600 )edit
1

The solution.

mohsen gravatar image mohsen  ( 2018-01-27 23:57:30 -0600 )edit

This helped me!

thorper gravatar image thorper  ( 2018-09-07 13:59:56 -0600 )edit

Glad to hear that!

mohsen gravatar image mohsen  ( 2018-09-10 10:36:15 -0600 )edit

This really helped me too!

apletta gravatar image apletta  ( 2019-07-03 06:24:49 -0600 )edit

This should be marked as accepted answer.

CoffeeKangaroo gravatar image CoffeeKangaroo  ( 2023-03-23 10:02:15 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2018-01-25 11:24:41 -0600

Seen: 6,992 times

Last updated: Jan 27 '18