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

Publisher or Subscriber inside a class [rosserial]

asked 2017-03-30 06:35:28 -0500

Emiliano gravatar image

updated 2019-01-17 18:04:56 -0500

jayess gravatar image

Hi, I'm using rosserial in Arduino and have a problem initializing the Publisher or Subscriber inside the class constructor:

 void setup() {
    DifferentialDriveRobot *my_robot = new DifferentialDriveRobot( );
 }

 void loop() {
    ...
 }

And the class is implemented as (in this example, with a subscriber):

    class DifferentialDriveRobot
    {
              ...
        public:
            ros::NodeHandle nh;
            ros::Subscriber<geometry_msgs::Twist> sub;
            ...
            void ddr_callback(const geometry_msgs::Twist& msg)  {...}

        DifferentialDriveRobot() {  // Constructor
                nh.initNode()
                sub("/cmd_vel_mux/input/teleop", ddr_callback);
                nh.subscribe(sub);
             }
    };

And the compiling errors are the following:

error: no matching function for call to 'ros::Subscriber<geometry_msgs::twist>::Subscriber()'

note: candidate expects 3 arguments, 0 provided

error: no match for call to '(ros::Subscriber<geometry_msgs::twist>) (const char [26], void (&)(const geometry_msgs::Twist&))'

sub("/cmd_vel_mux/input/teleop", ddr_callback);

I think that this is because of the initialization of the sub variable without any parameter. Should I declare it as a pointer?

NOTE: If I declare the ros::NodeHandle nh and ros::Subscriber<geometry_msgs::Twist> sub("/cmd_vel_mux/input/teleop", ddr_callback) in the main loop as global variables, the code works fine.

I'm not very familiarized using templates, so I don't know exactly if exists an good implementation for this problem in the ros_lib library.

Thanks for your help!


Update

Error message shown by the Arduino IDE when compile the answer of @DavidN:

Arduino: 1.6.12 (Linux), Board: "Arduino Leonardo"

In file included from /home/emiliano/catkin_ws/src/my_mobile_robot/from_keyboard_node-local_variables/from_keyboard_node-local_variables.ino:27:0:
DifferentialDriveRobot.h:45: error: invalid use of template-name 'ros::Subscriber' without an argument list
  ros::Subscriber sub;
  ^
sketch/DifferentialDriveRobot.h: In constructor 'DifferentialDriveRobot::DifferentialDriveRobot(DCMotor*, DCMotor*, double, double)':
DifferentialDriveRobot.h:67: error: 'sub' was not declared in this scope
  sub = nh.subscribe("/cmd_vel_mux/input/teleop", 1, &DifferentialDriveRobot::ddr_callback, this);
  ^
DifferentialDriveRobot.h:67: error: no matching function for call to 'ros::NodeHandle_<ArduinoHardware>::subscribe(const char [26], int, void (DifferentialDriveRobot::*)(const geometry_msgs::Twist&), DifferentialDriveRobot*)'
  sub = nh.subscribe("/cmd_vel_mux/input/teleop", 1, &DifferentialDriveRobot::ddr_callback, this);
                                                                                                ^
sketch/DifferentialDriveRobot.h:67:96: note: candidate is:
In file included from /home/emiliano/Arduino/libraries/ros_lib/ros.h:38:0,
                 from sketch/DifferentialDriveRobot.h:8,
                 from /home/emiliano/catkin_ws/src/my_mobile_robot/from_keyboard_node-local_variables/from_keyboard_node-local_variables.ino:27:
/home/emiliano/Arduino/libraries/ros_lib/ros/node_handle.h:352:12: note: template<class SubscriberT> bool ros::NodeHandle_<Hardware, MAX_SUBSCRIBERS, MAX_PUBLISHERS, INPUT_SIZE, OUTPUT_SIZE>::subscribe(SubscriberT&) [with SubscriberT = SubscriberT; Hardware = ArduinoHardware; int MAX_SUBSCRIBERS = 25; int MAX_PUBLISHERS = 25; int INPUT_SIZE = 512; int OUTPUT_SIZE = 512]
       bool subscribe(SubscriberT& s){
            ^
/home/emiliano/Arduino/libraries/ros_lib/ros/node_handle.h:352:12: note:   template argument deduction/substitution failed:
In file included from /home/emiliano/catkin_ws/src/my_mobile_robot/from_keyboard_node-local_variables/from_keyboard_node-local_variables.ino:27:0:
sketch/DifferentialDriveRobot.h:67:96: note:   candidate expects 1 argument, 4 provided
  sub = nh.subscribe("/cmd_vel_mux/input/teleop", 1, &DifferentialDriveRobot::ddr_callback, this);
                                                                                                ^
exit status 1
invalid use of template-name 'ros::Subscriber' without an argument list
edit retag flag offensive close merge delete

Comments

Comment from @DavidN:

According to this test under rosserial, there is definitely a way to declare subscriber without argument list: https://github.com/ros-drivers/rosser...

jayess gravatar image jayess  ( 2019-01-17 18:06:06 -0500 )edit

Is there any way to publish outside the void loop?

subarashi gravatar image subarashi  ( 2020-06-29 03:39:54 -0500 )edit

I think for the subscriber is easy, but for publishing is not easy. Is there any way to publish outside the void loop?

subarashi gravatar image subarashi  ( 2020-06-29 03:49:30 -0500 )edit
1

Would you create a new issue and point us there so we can give you precise feedback?

Emiliano gravatar image Emiliano  ( 2020-06-29 07:02:37 -0500 )edit

Thanks. I've created this one rosserial arduino

subarashi gravatar image subarashi  ( 2020-06-29 07:07:54 -0500 )edit

2 Answers

Sort by ยป oldest newest most voted
6

answered 2017-04-16 16:08:29 -0500

rreignier gravatar image

updated 2018-12-20 11:13:13 -0500

Hi,

According to this test: https://github.com/ros-drivers/rosser...

You should write:

class DifferentialDriveRobot
{
          ...
    public:
        ros::NodeHandle nh;
        ros::Subscriber<geometry_msgs::Twist, DifferentialDriveRobot> sub;
        ...
        void ddr_callback(const geometry_msgs::Twist& msg)  {...}

        DifferentialDriveRobot()
        : sub("/cmd_vel_mux/input/teleop", &DifferentialDriveRobot::ddr_callback, this)
        {  // Constructor
            nh.initNode()
            nh.subscribe(sub);
         }
};
edit flag offensive delete link more

Comments

Thanks a lot!! This implementation saved me a lot of memory!

Emiliano gravatar image Emiliano  ( 2017-04-16 17:54:42 -0500 )edit

I know this is a few years old, but I wonder if using initialization lists is the only approach? This solution worked well for me until I decided that I want the topic name to be different for each instance of my class. In that case, you could pass a char* variable as a parameter to the constructor. But what if you wanted to change only part of the topic name? For example "/cmd_vel_mux/input1/teleop" for instance 1 and "/cmd_vel_mux/input2/teleop" for instance 2. Possible but a bit messy in my opinion if the only solution is to use initialization lists. Would be nice have that line of code inside the body of the constructor itself. Any thoughts on alternative approaches?

aconstantinescu gravatar image aconstantinescu  ( 2021-01-05 17:00:15 -0500 )edit

This is possible if you create the NodeHandle, the subscribers and publishers on the heap. But might not be compatible with your platform. You could use std::shared_ptr<ros::NodeHandle>, std::shared_ptr<ros::Subscriber<geometry_msgs::Twist>> and initialize them in the constructor body.

rreignier gravatar image rreignier  ( 2021-01-07 02:07:51 -0500 )edit
1

answered 2017-04-06 03:09:19 -0500

DavidN gravatar image

updated 2017-04-06 03:25:27 -0500

You can try something like this:

class DifferentialDriveRobot
{
          ...
    public:
        ros::NodeHandle nh;
        ros::Subscriber sub;
        ...
        void ddr_callback(const geometry_msgs::Twist& msg)  {...}

    DifferentialDriveRobot() {  // Constructor
            nh.initNode()
            sub = nh.subscribe("/cmd_vel_mux/input/teleop", 1, &DifferentialDriveRobot::ddr_callback, this);
         }
};
edit flag offensive delete link more

Comments

I got some errors:

First, the sub declaration must have a <geometry_msgs::Twist>.

Second, I got the error: no matching function for call to 'ros::Subscriber<geometry_msgs::twist>::Subscriber()'. I think it's because there is only 1 constructor in subscriber.h (in arduino ros_lib package).

Emiliano gravatar image Emiliano  ( 2017-04-06 19:40:06 -0500 )edit

You mentioned "First, the sub declaration must have a <geometry_msgs::twist>", this is weird, because I have never had to set message type when declaring subscribers. Can you post the complete error message when you compile?

DavidN gravatar image DavidN  ( 2017-04-09 07:58:23 -0500 )edit

I put the error message in another answer because of the restrictions of this comment text.

Emiliano gravatar image Emiliano  ( 2017-04-09 08:52:36 -0500 )edit

Question Tools

4 followers

Stats

Asked: 2017-03-30 06:35:28 -0500

Seen: 2,797 times

Last updated: Jun 29 '20