Skip to content
This repository was archived by the owner on May 31, 2025. It is now read-only.

Fix a bug that causes an XmlRpc::XmlRpcException#928

Closed
afakihcpr wants to merge 1 commit intoros:kinetic-develfrom
afakihcpr:kinetic-devel
Closed

Fix a bug that causes an XmlRpc::XmlRpcException#928
afakihcpr wants to merge 1 commit intoros:kinetic-develfrom
afakihcpr:kinetic-devel

Conversation

@afakihcpr
Copy link
Copy Markdown
Contributor

@afakihcpr afakihcpr commented Nov 9, 2016

The exception is raised if the node is trying to subscribe to a topic after rosmaster dies. In this case, the node will be stuck in the while loop in ros::master::execute():

https://github.com/ros/ros_comm/blob/kinetic-devel/clients/roscpp/src/libros/master.cpp#L189

if the condition (!ros::isShuttingDown() && !XMLRPCManager::instance()->isShuttingDown()) becomes false, the loop would be exited and the function returns True although payload is invalid.

A simple example to reproduce:

#include "ros/ros.h"
#include "std_msgs/String.h"
#include <ros/topic.h>

void callback(const std_msgs::String::ConstPtr& msg)
{
  ROS_ERROR(msg->data.c_str());
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "test_node");
  ros::NodeHandle n;

  boost::shared_ptr<std_msgs::String const> msg;
  while (!(msg = ros::topic::waitForMessage<std_msgs::String>("some_topic", n, ros::Duration(2))) && ros::ok())
  {
    ROS_ERROR("Waiting for messages");
  }
  
  ros::spin();
  return 0;
}

If we run roscore, then run the above node, then kill roscore then try to stop the node with Ctrl-C we will get:
terminate called after throwing an instance of ' XmlRpc::XmlRpcException'

@dirk-thomas
FYI @mikepurvis @efernandez

@efernandez
Copy link
Copy Markdown
Contributor

I've discussed this with @afakihcpr, and there's a bug in execute that essentially leads to return true with an invalid `payload.

This could also impact lookupService in https://github.com/afakihcpr/ros_comm/blob/cb0d5fad8fd5ddbb6dcca0e108594bbc42e415b6/clients/roscpp/src/libros/service_manager.cpp#L315

However, a change in execute (other than the one already suggested by @afakihcpr) might be too big. Or at least it needs some discussion before doing it.

I give you my 👍 anyway. Nice finding.

@mikepurvis
Copy link
Copy Markdown
Member

Some related discussion in #836. Looks like @afakihcpr found the magic code path where execute returns true, but the payload is invalid— it occurs when the loop exits due to the ROS master shutting down:

ok = !ros::isShuttingDown() && !XMLRPCManager::instance()->isShuttingDown();

My preference would be to handle this in execute, by changing the highlighted line to instead be:

if (ros::isShuttingDown() || XMLRPCManager::instance()->isShuttingDown())
{
  return false;
}

I don't see this as a super-disruptive change; it is correcting a wrong behaviour in that execute should never return true unless the RPC succeeded and payload is valid.

The exception is raised  if the node is trying to subscribe to a topic after rosmaster dies.
@mikepurvis
Copy link
Copy Markdown
Member

Replaced by #938.

@mikepurvis mikepurvis closed this Jan 10, 2017
Sign up for free to subscribe to this conversation on GitHub. Already have an account? Sign in.

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

3 participants