[go: up one dir, main page]
More Web Proxy on the site http://driver.im/
Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

rosbag record --node crashes if monitored node dies violently #357

Closed
astaa-nrec opened this issue Feb 14, 2014 · 0 comments
Closed

rosbag record --node crashes if monitored node dies violently #357

astaa-nrec opened this issue Feb 14, 2014 · 0 comments
Assignees
Labels

Comments

@astaa-nrec
Copy link

To reproduce, compile the following two programs:

// talker.cpp
#include "ros/ros.h"
#include "std_msgs/Int32.h"

#include <sstream>

int main(int argc, char **argv)
{
  ros::init(argc, argv, "talker");
  ros::NodeHandle n;
  ros::Publisher chatter_pub = n.advertise<std_msgs::Int32>("chatter", 1000);
  ros::Rate loop_rate(10);

  int count = 0;
  while (ros::ok())
  {
    std_msgs::Int32 msg;
    msg.data = count;
    chatter_pub.publish(msg);
    ros::spinOnce();
    loop_rate.sleep();
    ++count;
  }

  return 0;
}
// listener.cpp
#include "ros/ros.h"
#include "std_msgs/Int32.h"

void chatterCallback(const std_msgs::Int32::ConstPtr& msg)
{
    ROS_INFO("I heard: [%d]", msg->data);
    if (msg->data == 30) {
        _exit(-1);
    }
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "listener");
  ros::NodeHandle n;
  ros::Subscriber sub = n.subscribe("chatter", 1000, chatterCallback);
  ros::spin();
  return 0;
}

Now, in four separate terminals:

$ roscore
$ rosbag record --node /listener -O test.bag
$ ./listener
$ ./talker

The rosbag process will exit with the exception "terminate called after throwing an instance of 'XmlRpc::XmlRpcException'" and leave a broken bag 'test.bag.active' that cannot be fixed by rosbag reindex.

The problem can be traced to the Recorder::doCheckMaster() function in ros_comm/tools/rosbag/src/recorder.cpp.

Changing line 570 fixes it:

- if (!c.isFault() && resp.size() > 0 && static_cast<int>(resp[0]) == 1)
+ if (!c.isFault() && resp.valid() && resp.size() > 0 && static_cast<int>(resp[0]) == 1)

Note also that there is an error in line 578:

ROS_ERROR("Node at: [%s] failed to return subscriptions.", static_cast<std::string>(resp[2]).c_str());

Here, resp is meant to refer to the response to the XmlRpc "lookupNode" call to master, but it actually refers to the "getSubscriptions" call. Thus, the error messsage does not print a URI, as intended.

@dirk-thomas dirk-thomas added the bug label May 5, 2014
@dirk-thomas dirk-thomas self-assigned this May 5, 2014
dirk-thomas added a commit that referenced this issue May 5, 2014
rsinnet pushed a commit to MisoRobotics/ros_comm that referenced this issue Jun 19, 2017
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Projects
None yet
Development

No branches or pull requests

2 participants