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

Revision history [back]

click to hide/show revision 1
initial version

I am a bit late. But actually, it is possible to use a subscriber within a class with rosserial.

The writing is a bit different than the usual ROS, it uses a template parameter.

See the following example:

#include <ros.h>
#include <std_msgs/UInt8.h>

ros::NodeHandle nh;

struct Control {
  Control(byte out, char* topic)
    : pin_out(out),
      sub(topic, &Control::callback, this)
  {}
  void init() {
    nh.subscribe(sub);
  }
  void callback(const std_msgs::UInt8& msg) {
    analogWrite(pin_out, msg.data);
  }

  byte pin_out;
  ros::Subscriber<std_msgs::UInt8, Control> sub;
};

Control throttle(1, "throttle");
Control transmission(2, "transmission");
Control steering(3, "steering");

void setup() {
  nh.initNode();
  throttle.init();
  transmission.init();
  steering.init();
}

void loop()
{}