Adding class callback function on Arduino [rosserial_arduino]

asked 2018-05-11 16:03:56 -0500

prex gravatar image

updated 2018-05-11 17:21:39 -0500

I'm having an issue with using a class function as my subscriber callback function on Arduino.

First, I'm wondering why there are differences between ROS classes and functions on Arduino and "normal" ROS installation on Linux. For example:

nh.initNode()

instead of

ros::init(argc, argv, "controller")

Or:

ros::Subscriber<std_msgs::Int32> relPos_subscriber("stepper_rel_pos", &Class::callback_fct, &class)

instead of

ros::Subscriber relPos_subscriber("stepper_rel_pos", 10, &Class::callback_fct, &class)

But my main concern is about using a class function as a callback for my subscriber, which is not in the same class and namespace. Before, it worked fine by using a callback function in the same class with "this" and the same namespace. But I couldn't find any help for my specific case.

I'm getting a large error message about the Subscriber. Last line:

no matching function for call to 'ros::Subscriber<std_msgs::int32>::Subscriber(const char [16], void (asc_node::Stepper::)(const std_msgs::Int32&), asc_node::Stepper)'

My node:

#include <ros.h>
#include "Stepper.h"
ros::NodeHandle nh;

asc_node::Stepper stepper; //creating the class object
ros::Subscriber<std_msgs::Int32> relPos_subscriber("stepper_rel_pos", &asc_node::Stepper::moveRel, &stepper);

nh.initNode();
nh.subscribe(relPos_subscriber);

My class function:

#include "Stepper.h"

namespace asc_node {
// Constructor & Destructor
void Stepper::moveRel(const std_msgs::Int32& message)
{
// do something
}

} /* namespace */

And my declaration in Stepper.h:

namespace asc_node {
class Stepper {
//...
void moveRel(const std_msgs::Int32& message);
}
} /* namespace */

I'm using Arduino IDE and an Arduino Uno Rev. 3.

Any help is appreciated.

edit retag flag offensive close merge delete

Comments

First, I'm wondering why there are differences between ROS classes and functions on Arduino and "normal" ROS installation on Linux.

that's easy: because rosserial and "normal ROS" have 'nothing' in common, apart from some terminology and naming. rosserial was implemented from scratch ..

gvdhoorn gravatar image gvdhoorn  ( 2018-05-12 03:04:39 -0500 )edit

.. and the methods were given similar names (and sometimes semantics), but apart from that it's a separate project.

It's essentially a facade: you can pretend your using ROS on your Arduino, but in reality it's a serial protocol that needs bridging to communicate with a real ROS nodegraph.

gvdhoorn gravatar image gvdhoorn  ( 2018-05-12 03:05:11 -0500 )edit