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

High level convenience classes for ros_serial

asked 2011-07-24 04:51:21 -0500

tom gravatar image

updated 2011-07-24 21:56:34 -0500

I thought I'd come up with two convenience classes to wrap up ROS communication in my ATmega1280 code. This may not be the most indispensible part of my project, but just for the fun of learning C++ template programming I thought I'd give it a try. My code is as follows:

#include <ros.h>

template <class T>
class ROSLogger {
public:
    ROSLogger(ros::NodeHandle* nh, char* topic, short pubFrequency);
    virtual ~ROSLogger();

    void advertise();
    void publish();
    T& getMsg();

private:
    ros::NodeHandle* nh_;
    ros::Publisher publisher_;
    T msg_;
    const char* topic_;
    short pubFrequency_;
};

template <class T>
ROSLogger<T>::ROSLogger(ros::NodeHandle* nh, char* topic, short pubFrequency) :
    nh_(nh),
    topic_(topic),
    pubFrequency_(pubFrequency),
    publisher_(topic_, static_cast<ros::Msg*>(&msg_)) {}

template <class T>
ROSLogger<T>::~ROSLogger() {}

template <class T>
void ROSLogger<T>::advertise() {
    nh_->advertise(publisher_);
}

template <class T>
T& ROSLogger<T>::getMsg() {
    return msg_;
}

template <class T>
void ROSLogger<T>::publish() {
    publisher_.publish(&msg_);
}

To use it one would create a ros::NodeHandle, initialize it, create a ROSLogger, advertise a topic and then publish data, as below.

unsigned char hello[13] = "hello world!";
ros::NodeHandle nh;
ROSLogger<std_msgs::String> rl(&nh, "test", 10);

void setup() {
  nh.initNode();
  rl.advertise();
}

void loop() {
  nh.spinOnce();
  rl.getMsg().data = hello;
  rl.publish();
}

At the end I'd create a vector of ROSLogger's in a containing class and their publish methods would fire only with the desired frequency automatically. Of course the latter is not yet implemented. Even if the added value is small, I'd still like to make it work. The point is, now it doesn't, and I don't know why. After running serial_node.py only an error appears:

[INFO] [WallTime: 1311526103.141689] ROS Serial Python Node
[INFO] [WallTime: 1311526103.149892] Connected on /dev/ttyUSB0
[ERROR] [WallTime: 1311526118.161632] Lost sync with device, restarting...
/opt/ros/diamondback/stacks/ros_comm/clients/rospy/src/rospy/topics.py:640: UserWarning: '' is not a legal ROS graph resource name. This may cause problems with other ROS tools
  super(Publisher, self).__init__(name, data_class, Registration.PUB)
Unable to register with master node [http://localhost:11311]: master may not be running yet. Will keep trying.

Any clues?

edit retag flag offensive close merge delete

2 Answers

Sort by ยป oldest newest most voted
0

answered 2011-07-24 22:04:08 -0500

tom gravatar image

updated 2011-07-25 00:34:50 -0500

OK, I figured this out. The problem was a C++ peculiarity when initializing class members with constructor's initialization list. The thing is, class members get initialized in the order of their declaration in class'es body, not in the order you name them in the initialization list (more on that eg. here). So changing the declaration this way solves the problem:

template <class T>
class ROSLogger {
public:
    ROSLogger(ros::NodeHandle* nh, char* topic, short pubFrequency);
    virtual ~ROSLogger();

    void advertise();
    void publish();
    T& getMsg();

private:
    ros::NodeHandle* nh_;
    const char* topic_;     //DECLARATION ORDER CHANGED HERE
    T msg_;
    ros::Publisher publisher_;
    short pubFrequency_;
};

The way I programmed this before publisher_ got initialized before topic_ was set, so this couldn't work.

edit flag offensive delete link more
1

answered 2011-07-24 10:03:55 -0500

fergs gravatar image

First, have you started a master by running "roscore" in a separate terminal? If not, nothing will go.

Second, you need an "nh.spinOnce()" in your loop(), otherwise things like time and topic negotiation will not be handled (the "lost sync with device" is due to the time synchronization not occuring, since you never call spinOnce).

edit flag offensive delete link more

Comments

Thanks fergs, that was not the issue, though. I edited my question and added spinOnce to avoid future confusion.
tom gravatar image tom  ( 2011-07-24 21:55:54 -0500 )edit

Question Tools

Stats

Asked: 2011-07-24 04:51:21 -0500

Seen: 1,685 times

Last updated: Jul 25 '11