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

Revision history [back]

Throwing exception in a subscribing node for a bad sensor initialization in a different node is an unusual approach, but I'd be curious if anyone can point to a major ros node that does that. http://wiki.ros.org/roscpp/Overview/Exceptions says "roscpp throws exceptions only in truly unexpected, programmer error conditions.".

But it is an interesting question so I set up an experiment and noticed some oddities with this- it looks like you can set up a try catch around ros::spin(), and then restart the spin after catching something.

I'm using timer callbacks rather than subscriber callbacks, perhaps they behave completely differently with exceptions.

#include <ros/ros.h>

ros::Time start;
int count = 0;

void printTimeDiff(const int i, const ros::TimerEvent& e)
{
  ROS_INFO_STREAM("Callback " << i << " triggered "
      << ros::Time::now() - start << " "
      << (e.current_expected - start).toSec() << " "
      << (e.current_real - start).toSec());
}

void callback1(const ros::TimerEvent& e)
{
  count++;
  printTimeDiff(1, e);
  if (count == 4)
  { 
    ROS_WARN_STREAM("throwing exception");
    throw 10;
  }
}

void callback2(const ros::TimerEvent& e)
{     
  printTimeDiff(2, e);
}

void callback3(const ros::TimerEvent& e)
{     
  printTimeDiff(3, e);
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "test");
  ros::NodeHandle n;
  start = ros::Time::now();

  ros::Timer timer1 = n.createTimer(ros::Duration(0.1), callback1);
  ros::Timer timer2 = n.createTimer(ros::Duration(0.1), callback2);
  // ros::Timer timer3 = n.createTimer(ros::Duration(0.5), callback3);

  while (ros::ok())
  {
    try {
      ros::spin();
    }
    catch (int e)
    {
      ROS_ERROR_STREAM("caught exception: " << e);
    }
  }
  return 0;
}

When I run the above neither callback is called after the exception, presumably I'd have to set them both up again. But if I change the timer2 duration to trigger the first callback after the exception occurs then it will trigger as expected. Or if I uncomment timer3 (which is first triggered after the exception) then both timer2 and timer3 will be triggered after the exception.

Throwing exception in a subscribing node for a bad sensor initialization in a different node is an unusual approach, but I'd be I'm curious if anyone can point to a major ros node that does that. http://wiki.ros.org/roscpp/Overview/Exceptions says "roscpp throws exceptions only in truly unexpected, programmer error conditions.".

But it is an interesting question so I set up an experiment and noticed some oddities with this- it looks like you can set up a try catch around ros::spin(), and then restart the spin after catching something.

I'm using timer callbacks rather than subscriber callbacks, perhaps they behave completely differently with exceptions.

#include <ros/ros.h>

ros::Time start;
int count = 0;

void printTimeDiff(const int i, const ros::TimerEvent& e)
{
  ROS_INFO_STREAM("Callback " << i << " triggered "
      << ros::Time::now() - start << " "
      << (e.current_expected - start).toSec() << " "
      << (e.current_real - start).toSec());
}

void callback1(const ros::TimerEvent& e)
{
  count++;
  printTimeDiff(1, e);
  if (count == 4)
  { 
    ROS_WARN_STREAM("throwing exception");
    throw 10;
  }
}

void callback2(const ros::TimerEvent& e)
{     
  printTimeDiff(2, e);
}

void callback3(const ros::TimerEvent& e)
{     
  printTimeDiff(3, e);
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "test");
  ros::NodeHandle n;
  start = ros::Time::now();

  ros::Timer timer1 = n.createTimer(ros::Duration(0.1), callback1);
  ros::Timer timer2 = n.createTimer(ros::Duration(0.1), callback2);
  // ros::Timer timer3 = n.createTimer(ros::Duration(0.5), callback3);

  while (ros::ok())
  {
    try {
      ros::spin();
    }
    catch (int e)
    {
      ROS_ERROR_STREAM("caught exception: " << e);
    }
  }
  return 0;
}

When I run the above neither callback is called after the exception, presumably I'd have to set them both up again. But if I change the timer2 duration to trigger the first callback after the exception occurs then it will trigger as expected. Or if I uncomment timer3 (which is first triggered after the exception) then both timer2 and timer3 will be triggered after the exception.

Throwing exception in a subscribing node for a bad sensor initialization in a different node is an unusual approach, I'm curious if anyone can point to a major ros node that does that. http://wiki.ros.org/roscpp/Overview/Exceptions says "roscpp throws exceptions only in truly unexpected, programmer error conditions.".

But it is an interesting question so I set up an experiment and noticed some oddities with this- it looks like you can set up a try catch around ros::spin(), and then restart the spin after catching something.

I'm using timer callbacks rather than subscriber callbacks, perhaps they behave completely differently with exceptions.

#include <ros/ros.h>

ros::Time start;
int count = 0;

void printTimeDiff(const int i, const ros::TimerEvent& e)
{
  ROS_INFO_STREAM("Callback " << i << " triggered "
      << ros::Time::now() - start << " "
      << (e.current_expected - start).toSec() << " "
      << (e.current_real - start).toSec());
}

void callback1(const ros::TimerEvent& e)
{
  count++;
  printTimeDiff(1, e);
  if (count == 4)
  { 
    ROS_WARN_STREAM("throwing exception");
    throw 10;
  }
}

void callback2(const ros::TimerEvent& e)
{     
  printTimeDiff(2, e);
}

void callback3(const ros::TimerEvent& e)
{     
  printTimeDiff(3, e);
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "test");
  ros::NodeHandle n;
  start = ros::Time::now();

  ros::Timer timer1 = n.createTimer(ros::Duration(0.1), callback1);
  ros::Timer timer2 = n.createTimer(ros::Duration(0.1), callback2);
  // ros::Timer timer3 = n.createTimer(ros::Duration(0.5), callback3);

  while (ros::ok())
  {
    try {
      ros::spin();
    }
    catch (int e)
    {
      ROS_ERROR_STREAM("caught exception: " << e);
    }
  }
  return 0;
}

When I run the above neither callback is called after the exception, presumably I'd have to set them both up again. But if I change the timer2 duration to trigger the first callback after the exception occurs then it will trigger as expected. Or if I uncomment timer3 (which is first triggered after the exception) then both timer2 and timer3 will be triggered after the exception.

Update using real subscribers

So the timer callbacks don't generalize, ros subscribers behave fine after an exception:

void printTimeDiff(const int i, const int j)
{
  ROS_INFO_STREAM("Callback " << i << " triggered "
      << ros::Time::now() - start << " " << j);
}

void callback1(const std_msgs::Int32::ConstPtr& e)
{
  count++;
  printTimeDiff(1, e->data);
  if (count == 4)
  {
    ROS_WARN_STREAM("throwing exception");
    throw 10;
  }
}

void callback2(const std_msgs::Int32::ConstPtr& e)
{
  printTimeDiff(2, e->data);
}

void callback3(const std_msgs::Int32::ConstPtr& e)
{
  printTimeDiff(3, e->data);
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "test");
  ros::NodeHandle n;
  start = ros::Time::now();

  ros::Subscriber s1 = n.subscribe("topic1", 1, callback1);
  ros::Subscriber s2 = n.subscribe("topic2", 1, callback2);
  ros::Subscriber s3 = n.subscribe("topic3", 1, callback3);
...

And some python to publish:

#!/usr/bin/env python

import rospy

from std_msgs.msg import Int32

rospy.init_node('pub_ints')

p1 = rospy.Publisher("topic1", Int32, queue_size=1)
p2 = rospy.Publisher("topic2", Int32, queue_size=1)
p3 = rospy.Publisher("topic3", Int32, queue_size=1)

count = 0
while not rospy.is_shutdown():
    p1.publish(Int32(1))
    p2.publish(Int32(2))
    rospy.sleep(0.5)
    count += 1
    if (count % 5 == 0):
        p3.publish(Int32(3))