ros / roscpp_core

ros distribution sandbox
88 stars 116 forks source link

Durations not printing out properly #92

Closed pbeeson closed 5 years ago

pbeeson commented 5 years ago
double timer = 49.9999999999;
std::cout << timer<<" "<<ros::Duration(timer)<<" "<<ros::Duration(timer).toSec()<<" "<<ros::Duration(ros::Rate(1/timer))<<" "<<ros::Time(timer));

Output: 50 49.1000000000 50 50.000000000 50.000000000

pbeeson commented 5 years ago

Oddly Timer works ok, even though they look to have similar operator<< definitions.

#include <ros/ros.h>

int main(int argc, char** argv)
{
  ros::init(argc, argv, "ik_tests");

  typedef std::numeric_limits< double > dbl;
  std::cout.precision(dbl::max_digits10);

  double timer=49;

  for (uint i=1; i <= 14; i++) {
    timer+=9/pow(10,i);
    std::cout << timer<<" "<<ros::Duration(timer)<<" "<<ros::Time(timer)<<"\n";
  }

  return 0;
}

Output:

49.899999999999999 49.900000000 49.900000000
49.990000000000002 49.990000000 49.990000000
49.999000000000002 49.999000000 49.999000000
49.999900000000004 49.999900000 49.999900000
49.999990000000004 49.999990000 49.999990000
49.999999000000003 49.999999000 49.999999000
49.999999900000006 49.999999900 49.999999900
49.999999990000006 49.999999990 49.999999990
49.999999999000003 49.999999999 49.999999999
49.999999999900005 49.1000000000 50.000000000
49.999999999990003 49.1000000000 50.000000000
49.999999999999005 49.1000000000 50.000000000
49.999999999999908 49.1000000000 50.000000000
50 50.000000000 50.000000000
pbeeson commented 5 years ago

I believe the reason why this works for Time() but not for Duration() if that the fromSec() definition of Duration is not as rigorous as the one for Time in terms of handling rounding errors. This seems like a Major issue if this is also affecting Duration math operations.

time.h:

    T& fromSec(double t) {
      int64_t sec64 = (int64_t)floor(t);
      if (sec64 < 0 || sec64 > UINT_MAX)
        throw std::runtime_error("Time is out of dual 32-bit range");
      sec = (uint32_t)sec64;
      nsec = (uint32_t)boost::math::round((t-sec) * 1e9);
      // avoid rounding errors
      sec += (nsec / 1000000000ul);
      nsec %= 1000000000ul;
      return *static_cast<T*>(this);
    }

duration.h:

  template<class T>
  T& DurationBase<T>::fromSec(double d)
  {
    int64_t sec64 = (int64_t)floor(d);
    if (sec64 < INT_MIN || sec64 > INT_MAX)
      throw std::runtime_error("Duration is out of dual 32-bit range");
    sec = (int32_t)sec64;
    nsec = (int32_t)(nearbyint((d - (double)sec)*1000000000));
    return *static_cast<T*>(this);
  }
pbeeson commented 5 years ago

Actually, what happens in the duration above is that the nearbyint() call on 0.9999999999*1e9 returns 1e9, which is 1 second, but then on printing the seconds are printed, then a ".", the nanoseconds are printed. But there are too many nanoseconds. The Time() function properly goes back and adds any nsec >= 1e9 to the seconds column.

Additionally, in a fix for this, in both Time and Duration either the round() as in the Time should be used or the nearby() as in Duration should be used for consistency. These won't return the same results by default for 0.5.

pbeeson commented 5 years ago

Also, duration.h fromSec() just seems wrong in that durations can be negative, so the first floor() call on a negative double rounds down to the lower negative number.

dirk-thomas commented 5 years ago

Addressed by #93.