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

Revision history [back]

click to hide/show revision 1
initial version

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);
}