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

What is the correct way to do stuff before a node is shutdown? [closed]

asked 2012-02-14 23:20:42 -0500

dornhege gravatar image

updated 2012-02-16 00:23:33 -0500

I want to do some shutting down code for my node. It is important that I am still fully connected to ROS while that is happening, so putting stuff just after the main loop is not an option.

Currently I would pass NoSigIntHandler to ros::init, install my own SIGINT handler, do stuff there and then call ros::shutdown.

Is this correct, i.e. the intended way or is there a better solution?

Update: I tested this and it works fine for pressing Ctrl-C even from roslaunch. For me this is OK right now.

The only thing that does not work is what Lorenz hinted at: rosnode kill seems to use another method, I get:

[ WARN] [1329394338.937166789, 61.017000000]: Shutdown request received.
[ WARN] [1329394338.937223749, 61.017000000]: Reason given for shutdown: [user request]

and my SIGINT handler is not called. I could try to work around this by checking ros::isShuttingDown and trying to shutdown my stuff while that is happening, but that doesn't seem safe to me.

edit retag flag offensive reopen merge delete

Closed for the following reason the question is answered, right answer was accepted by Procópio
close date 2019-10-25 10:55:40.516043

Comments

I see at least one (possible) problem with your solution: will it handle a rosnode kill command, i.e. a shutdown triggered via xmlrpc? I don't know a better solution though.

Lorenz gravatar image Lorenz  ( 2012-02-15 00:29:30 -0500 )edit

Seems reasonable to me.

joq gravatar image joq  ( 2012-02-15 01:29:18 -0500 )edit

@Lorenz: Depends on what rosnode kill does. Does it send SIGINT/SIGTERM? I'll play around with this tomorrow.

dornhege gravatar image dornhege  ( 2012-02-15 12:27:39 -0500 )edit

Rosnode kill cannot send SIGINT if the node is not owned by the user executing rosnode or if the node is running on a different computer. As far as I know, it uses the shutdown XMLRPC call (http://www.ros.org/wiki/ROS/Slave_API).

Lorenz gravatar image Lorenz  ( 2012-02-16 00:04:32 -0500 )edit

Yep, just found that out by trying. The only question left would be: Is it possible to hook in there and stop the shutdown until I am done. I'm OK with Ctrl-C handling for now as I don't use rosnode kill.

dornhege gravatar image dornhege  ( 2012-02-16 00:26:26 -0500 )edit

2 Answers

Sort by » oldest newest most voted
21

answered 2012-02-16 12:39:29 -0500

Patrick Mihelich gravatar image

There are two normal ways to tell a node to shut down:

  • SIGINT signal. Used by roslaunch or when you do Ctrl-C.
  • Shutdown XMLRPC call. Used by rosnode kill.

If you want to cover all your bases, you need to override roscpp's handlers for both. In practice, most people seem to just override SIGINT, probably because it's actually documented and rosnode kill is less-used.

What roscpp really needs is an "on shutdown" callback. That's ticketed here: https://code.ros.org/trac/ros/ticket/3417

In the meantime, it is possible (if a little messy) to do this correctly. An example is the nodelet.cpp code. The relevant parts look like:

#include <signal.h>
#include <ros/ros.h>
#include <ros/xmlrpc_manager.h>

// Signal-safe flag for whether shutdown is requested
sig_atomic_t volatile g_request_shutdown = 0;

// Replacement SIGINT handler
void mySigIntHandler(int sig)
{
  g_request_shutdown = 1;
}

// Replacement "shutdown" XMLRPC callback
void shutdownCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result)
{
  int num_params = 0;
  if (params.getType() == XmlRpc::XmlRpcValue::TypeArray)
    num_params = params.size();
  if (num_params > 1)
  {
    std::string reason = params[1];
    ROS_WARN("Shutdown request received. Reason: [%s]", reason.c_str());
    g_request_shutdown = 1; // Set flag
  }

  result = ros::xmlrpc::responseInt(1, "", 0);
}

int main(int argc, char** argv)
{
  // Override SIGINT handler
  ros::init(argc, argv, "MyNode", ros::init_options::NoSigintHandler);
  signal(SIGINT, mySigIntHandler);

  // Override XMLRPC shutdown
  ros::XMLRPCManager::instance()->unbind("shutdown");
  ros::XMLRPCManager::instance()->bind("shutdown", shutdownCallback);

  // Create publishers, subscribers, etc.

  // Do our own spin loop
  while (!g_request_shutdown)
  {
    // Do non-callback stuff

    ros::spinOnce();
    usleep(100000);
  }

  // Do pre-shutdown tasks

  ros::shutdown();
}
edit flag offensive delete link more

Comments

Is this in the documentation? I couldn't find it. If not, it should be added, IMO.

cpagravel gravatar image cpagravel  ( 2017-04-19 13:47:19 -0500 )edit

There ought to be a ros::NodeHandler nh; in there in order for the node to appear under rosnode list and be rosnode killable.

lucasw gravatar image lucasw  ( 2017-07-13 12:02:06 -0500 )edit

Also http://docs.ros.org/kinetic/api/nodel... could replace the dead nodelet.cpp link, but is also more complicated.

lucasw gravatar image lucasw  ( 2017-07-13 12:08:48 -0500 )edit

does anyone know if that ticket (https://code.ros.org/trac/ros/ticket/...) still exists?

khaiyichin gravatar image khaiyichin  ( 2019-10-25 10:26:14 -0500 )edit

@khaiyichin it does not exist. Bear in mind that this discussion is 7 years old.

Procópio gravatar image Procópio  ( 2019-10-25 10:54:50 -0500 )edit
1

answered 2012-02-16 01:08:23 -0500

Thomas gravatar image

updated 2012-02-16 01:08:47 -0500

If you look at roscpp, the current handler on SIGINT just call ros::requestShutdown() so you should fine be with your current solution.

See: https://code.ros.org/svn/ros/stacks/ros_comm/tags/electric/clients/cpp/roscpp/src/libros/init.cpp

On a different point, requesting a shutdown on ROS just switch a boolean variable (see the previous source code) so IMHO it should be safe to continue using ROS after resquestShutdown is called... Maybe someone can confirm?

edit flag offensive delete link more

Comments

What I'm worried about is: For how long. The shutdown will surely happen quite timely and I have no guarantees. I have digged a bit through the code. I could try getting a lock on the global shutdown mutex, but interfering here seems quite risky to me.

dornhege gravatar image dornhege  ( 2012-02-16 01:48:10 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2012-02-14 23:20:42 -0500

Seen: 17,181 times

Last updated: Feb 16 '12