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

ROS, class with callback methods

asked 2018-02-09 07:10:37 -0500

edamondo gravatar image

updated 2018-02-09 13:14:06 -0500

jayess gravatar image

Hi,

I wanted to create a class which initializes a node and has some callback that would be called when I do ros::spin. The one implemented bellow doesn't compile (why?). It tells me :

invalid use of non-static member function ‘void EKF_node::chatterCallback(const ConstPtr&)’ 
ros::Subscriber sub_camera = n.subscribe("chatter", 1000, chatterCallback);

Also, it seems that if I do ros::spin in the main, it won't call the callback methods. How should I fix this stuff?

#include "ros/ros.h"                                                                                                                                                 
#include <message_filters/subscriber.h>                                                                                                                              
#include <message_filters/synchronizer.h>                                                                                                                            
#include <message_filters/sync_policies/approximate_time.h>                                                                                                          
#include <std_msgs/String.h>                                                                                                                                         

using namespace message_filters;                                                                                                                                     
using namespace std_msgs;                                                                                                                                            
using namespace std;                                                                                                                                                 

class EKF_node                                                                                                                                                       
{                                                                                                                                                                    
        public:                                                                                                                                                      
                // constructor                                                                                                                                       
                EKF_node(int argc,char** argv)                                                                                                                       
                {                                                                                                                                                    
                        ros::init(argc, argv, "listenerMultipleTopics");                                                                                             
                        ros::NodeHandle n;                                                                                                                           

                        ros::Subscriber sub_camera = n.subscribe("chatter", 1000, chatterCallback);                                                                  
                        ros::Subscriber sub_imu = n.subscribe("chatter2", 1000, chatterCallback2);                                                                   
                }                                                                                                                                                    


                // callback1                                                                                                                                         
                void chatterCallback(const std_msgs::String::ConstPtr& msg)                                                                                          
                {                                                                                                                                                    
                        ROS_INFO("I heard: [%s]", msg->data.c_str());                                                                                                
                }                                                                                                                                                    
                // callback2                                                                                                                                         
                void chatterCallback2(const std_msgs::String::ConstPtr& msg)                                                                                         
                {                                                                                                                                                    
                        ROS_INFO("I heard from the second chatter: [%s]", msg->data.c_str());                                                                        
                }                                                                                                                                                    
        private:                                                                                                                                                     
                // vector containing the outputs                                                                                                                     
                vector<string> y;                                                                                                                                    
};                                                                                                                                          

int main(int argc, char **argv)                                                                                                                                      
{                                                                                                                                                                                  
        ros::spin();                                                                                                                                                 
        return 0;           
}

edit :

So I followed the nice suggestions from Thomas and Airuno and I try to do a small code that puts the received string in a string vector and than in the main loop I wan't to display this string components.

The first problem is when I execute this listener node, I cannot use ctrl+c to stop the node.

The second thing is that between two displays of the vectors there are a lot of white lines that are displayed.

Note that the talker I use are simply the talkers from the tutorial https://wiki.ros.org/ROS/Tutorials/WritingPublisherSubscriber%28c%2B%2B%29

#include "ros/ros.h"                                                                                                                                                 
#include <message_filters/subscriber.h>                                                                                                                              
#include <message_filters/synchronizer.h>                                                                                                                            
#include <message_filters/sync_policies/approximate_time.h>                                                                                                          
#include <std_msgs/String.h>                                                                                                                                         

using namespace message_filters;                                                                                                                                     
using namespace std_msgs;                                                                                                                                            
using namespace std;                                                                                                                                                 

class EKF_node                                                                                                                                                       
{                                                                                                                                                                    
        public:                                                                                                                                                      
                // constructor                                                                                                                                       
                EKF_node()                                                                                                                                           
                        : y(2)                                                                                                                                       
                {                                                                                                                                                    
                        ros::NodeHandle n;                                                                                                                           

                        sub_camera = n.subscribe("chatter", 1000, &EKF_node::chatterCallback, this);                                                                 
                        sub_imu = n.subscribe("chatter2", 1000, &EKF_node::chatterCallback2, this);                                                                  
                }                                                                                                                                                    


                // callback1                                                                                                                                         
                void chatterCallback(const std_msgs::String::ConstPtr& msg)                                                                                          
                {                                                                                                                                                    
                        //ROS_INFO("I heard: [%s]", msg->data.c_str());                                                                                              
                        y[0] = msg->data.c_str();                                                                                                                    
                }                                                                                                                                                    
                // callback2                                                                                                                                         
                void chatterCallback2(const std_msgs::String::ConstPtr& msg)                                                                                         
                {                                                                                                                                                    
                        //ROS_INFO("I heard from the second chatter: [%s]", msg->data.c_str());                                                                      
                        y[1] = msg->data.c_str();                                                                                                                    
                }                                                                                                                                                    
                //private:                                                                                                                                           
                // vector containing the outputs                                                                                                                     
                vector<string> y;
                ros::Subscriber sub_camera;                                                                                                                          
                ros::Subscriber sub_imu;                                                                                                                             
};                                                                                                                                                                   

int main(int argc, char **argv)                                                                                                                                      
{                                                                                                                                                                    

        ros::init(argc, argv, "listenerMultipleTopics");                                                                                                             
        EKF_node myNode;                                                                                                                                             
        ros::Rate r(10);                                                                                                                                             

        while(ros::ok)                                                                                                                                               
        {                                                                                                                                                            
                ros::spinOnce;                                                                                                                                       
                cout << myNode.y[0] << endl << myNode.y[1] << endl;                                                                                                  
                r.sleep();                                                                                                                                           
        }                                                                                                                                                            
        return 0;                                                                                                                                                    
}
edit retag flag offensive close merge delete

Comments

Your update seems like a new question. But you might be able to change to ros::spinOnce();.

Thomas D gravatar image Thomas D  ( 2018-02-09 11:56:41 -0500 )edit

Yes, but the ctrl+c still doesn't work. Actually I am suprised it even compiled without the parenthesis for spinOnce.

edamondo gravatar image edamondo  ( 2018-02-09 13:57:58 -0500 )edit

ctrl-C doesn't work because you're checking that the ros::ok function exists instead of calling it. Try while(ros::ok())

ahendrix gravatar image ahendrix  ( 2018-02-10 11:55:35 -0500 )edit

damned! Thanks a lot ahendrix, this is absolutely correct!

edamondo gravatar image edamondo  ( 2018-02-11 16:44:51 -0500 )edit

2 Answers

Sort by » oldest newest most voted
8

answered 2018-02-09 08:47:51 -0500

Thomas D gravatar image

updated 2018-02-09 08:48:51 -0500

The build error is likely because you need to specify that your callbacks are member functions: n.subscribe("chatter", 1000, &EKF_node::chatterCallback, this);. I did not test that your code compiles with that type of change.

You don't get to your callbacks if ros::spin() is in main() because your subscribers are not member variables. They go out of scope as soon as you leave your constructor. When you put ros::spin() (which blocks) in your constructor you do not leave the constructor and the subscribers do not go out of scope. You should make your subscribers member variables and spin from main.

I normally see ros::init() in main also.

And you need to create an instance of your class in main, as answered by @Airuno2L.

edit flag offensive delete link more

Comments

Thanks Thomas, if I specify that the callbacks are member function, it compiles just fine. But could you explain why I actually have to do this. I would be interested in understanding it.

edamondo gravatar image edamondo  ( 2018-02-09 10:19:42 -0500 )edit

The subscribers are using boost::bind, per the node handle API.

Thomas D gravatar image Thomas D  ( 2018-02-09 11:45:20 -0500 )edit

Oh, okay. I also just found this : https://wiki.ros.org/roscpp_tutorials... .

edamondo gravatar image edamondo  ( 2018-02-09 13:56:54 -0500 )edit
1

answered 2018-02-09 07:25:34 -0500

Airuno2L gravatar image

Hi,

This isn't your problem, but you never create an instance of your class. Your program starts at the main line, and does ros::spin(). All the code in you class is never ran. You should have something like

EKF_node my_EKF();

Before the spin.

As for the error you're seeing, there is a trick to using member functions as callbacks, that is detailed here.

edit flag offensive delete link more

Comments

That is true Airuno2L

edamondo gravatar image edamondo  ( 2018-02-09 07:50:02 -0500 )edit

Question Tools

1 follower

Stats

Asked: 2018-02-09 07:10:37 -0500

Seen: 9,647 times

Last updated: Feb 09 '18