0
$\begingroup$

Rosanswers logo

I have written a ROS node, just publishing to a topic, using roscpp that runs on a separate machine to the ROS master. It is based on the simple publisher/subscriber tutorials. If the ROS master gets restarted my node no-longer appears when I query the new master with rosnode list. It needs to be able to detect that the ROS master has gone down and re-advertise it's topics when it comes back up. I haven't managed to get this to work without killing and restarting my entire process.

I can detect that the connection to the ROS master has dropped by periodically checking ros::master::check () (would love a better way). When it returns true again after the master comes back up, none of the following work:

  1. Call .advertise() on the old NodeHandle and get a new publisher. I thought this would work but it doesn't seem to.

  2. Create a new NodeHandle and re-advertise on that.

  3. Re-run ros::init

  4. Call ros::shutdown and then call ros::init core dumps.

Also: I'm assuming ros::master::check () returns false if the connection is interrupted as well as if the master is restarted, do I need to handle that case differently or will re-advertising on the same master be OK?


Originally posted by techno74 on ROS Answers with karma: 90 on 2015-02-03

Post score: 6


Original comments

Comment by EpicZa on 2018-03-21:
Ever find a solution to this?

$\endgroup$

1 Answer 1

0
$\begingroup$

Rosanswers logo

Wrapping the ros::init() and NodeHandle creation seems to work. In a bigger project where I have passed the ROS nodeHandle around and attached publishers and things to it I can't get it to work yet.

main.c

#include "ros/ros.h"

#include "std_msgs/String.h"

#include "rosConnection.H"

#include <sstream>
#include <iostream>
using namespace std;

int main(int argc, char **argv)
{
    int count = 0;
    bool reconnect = false;

    do
    {
        rosConnectionHandler_t rc (argc, argv);

        ros::Publisher chatter_pub = rc.nodeHandle ()->advertise<std_msgs::String>("chatter", 1000);

        ros::Rate loop_rate(10);

        while (ros::ok() && ros::master::check())
        {
            std_msgs::String msg;

            stringstream ss;
            ss << "hello world " << count;
            msg.data = ss.str();
            cout << msg.data << endl;

            chatter_pub.publish(msg);
            ros::spinOnce();
            loop_rate.sleep();
            ++count;
        }

        cout << "ROS OK: " << (ros::ok()?"true":"false") << endl;
        cout << "MASTER UP: " << (ros::master::check()?"true":"false") << endl;

        reconnect = !ros::master::check() && ros::ok();

        if (reconnect)
            cout << "Attempting to reconnect" << endl;

    } while (reconnect);

    return 0;
}

rosConnection.H

#pragma once

#include <ros/ros.h>

class rosConnectionHandler_t
{
    public:
        rosConnectionHandler_t (int argc_, char** argv_)
        {
            ros::init (argc_, argv_, "testnode");

            nh = new ros::NodeHandle();
        }

        ~rosConnectionHandler_t ()
        {
            delete nh;
        }

        ros::NodeHandle *nodeHandle() { return nh; };

    private:
        ros::NodeHandle *nh;
};

Originally posted by techno74 with karma: 90 on 2015-02-05

This answer was ACCEPTED on the original site

Post score: 1


Original comments

Comment by VictorLamoine on 2018-03-30:
This works but for some reason ROS_INFO_STREAM, ROS_WARN_STREAM and ROS_ERROR_STREAM does not seem to work after the first re-connection

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge you have read our privacy policy.