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

Exception thrown while processing service call: Time is out of dual 32-bit range

asked 2015-05-18 16:54:56 -0600

ajain gravatar image

I am doing a very simple implementation of ROS service. There are two nodes, server and client node and the only main variable is that I am using rosbags for streaming data used by callback method on server side. I am getting the following error on some callbacks -

Exception thrown while processing service call: Time is out of dual 32-bit range

Can someone throw some light on why am I getting this error and how can I fix this for my service callback to work properly?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
7

answered 2015-05-28 22:27:46 -0600

crazyorc gravatar image

The exception is because Internally ros::Time objects use int64_t variables and cast to uint32_t when returning the result. When a time value is negative, the value exceeds what an uint32_t variable can represent. The result is the exception you are seeing is thrown.

This sample code that generates the exception you are seeing.

try {
  ros::Time test = ros::Time::now() - ros::Duration(0.01);
}
catch(std::runtime_error& ex) {
  ROS_ERROR("Exception: [%s]", ex.what());
}

Possible solutions:

  1. Wrap your code in try-catch blocks and deal with the resulting issues
  2. Call toSec() on time/duration objects and do the math manually

TL;DR

Here's where the exception is thrown (source here)

void normalizeSecNSecUnsigned(int64_t& sec, int64_t& nsec)
{
  int64_t nsec_part = nsec % 1000000000L;
  int64_t sec_part = sec + nsec / 1000000000L;
  if (nsec_part < 0)
  {
      nsec_part += 1000000000L;
      --sec_part;
  }

  if (sec_part < 0 || sec_part > UINT_MAX)
    throw std::runtime_error("Time is out of dual 32-bit range");

  sec = sec_part;
  nsec = nsec_part;
}

This code is one of several places where the exception might be generated. Subtraction is implemented as "negative addition". (source here)

template<class T, class D>
T TimeBase<T, D>::operator-(const D &rhs) const
{
  return *static_cast<const T*>(this) + ( -rhs);
}

template<class T, class D>
T TimeBase<T, D>::operator+(const D &rhs) const
{
  int64_t sec_sum  = (int64_t)sec  + (int64_t)rhs.sec;
  int64_t nsec_sum = (int64_t)nsec + (int64_t)rhs.nsec;

  // Throws an exception if we go out of 32-bit range
  normalizeSecNSecUnsigned(sec_sum, nsec_sum);

  // now, it's safe to downcast back to uint32 bits
  return T((uint32_t)sec_sum, (uint32_t)nsec_sum);
}
edit flag offensive delete link more

Comments

1

The explanation is correct. However, I would use another solution as this exception is a sign of something going actually wrong unless negative time has meaning. So, the best would be, figure out, where the exceptions happen and check the time values/durations involved.

dornhege gravatar image dornhege  ( 2015-05-29 02:24:09 -0600 )edit

Excellent point. My experience bias blinded me a little. Playback of rosbags has been the source of many of these exceptions for me.

crazyorc gravatar image crazyorc  ( 2015-05-29 10:25:21 -0600 )edit

I've had the same issue recently, running bags on a set of code that I know works. Any ideas on how to determine which clock times are wrong? I'm using the usual

rosparam set use_sim_time rosbag play --clock bagfile.bag

stevenwaslander gravatar image stevenwaslander  ( 2015-07-02 20:07:12 -0600 )edit

I'd just dump the actual time stamps. Usually it's something, where 12.0 is compared to 173939302.2.

dornhege gravatar image dornhege  ( 2015-07-03 03:37:23 -0600 )edit

Thanks, that did it. It appears there was an issue using ros::Time::now().toNSec() to populate the pcl point cloud header.stamp using the latest everything in Ubuntu 14.04. Started happening about two weeks ago, will confirm versions and post elsewhere.

stevenwaslander gravatar image stevenwaslander  ( 2015-07-03 06:47:06 -0600 )edit
2

Found a cleaner answer, see this post

#include <pcl_conversions/pcl_conversions.h> ... pcl_conversions::toPCL(ros::Time::now(), point_cloud_msg->header.stamp);

stevenwaslander gravatar image stevenwaslander  ( 2015-07-03 07:32:30 -0600 )edit

@crazyorc the example you provide does not cause any issues on my machine (Ubuntu 14.04.3 64 bit, ROS Indigo).

bit-pirate gravatar image bit-pirate  ( 2016-03-21 09:12:04 -0600 )edit

@bit-pirate Consider yourself lucky! A lot has changed in the past year for both ROS and Ubuntu but I don't see any changes to fix this. I would expect my example to still fail since I don't see any changes (rushed glance), but if it works now that's awesome.

crazyorc gravatar image crazyorc  ( 2016-03-28 19:15:36 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2015-05-18 16:54:56 -0600

Seen: 16,061 times

Last updated: May 28 '15