From 2ef78cd35fbb7097992f772cbbbb689926ecf574 Mon Sep 17 00:00:00 2001 From: BrutusTT Date: Tue, 20 Mar 2018 17:35:35 +0000 Subject: [PATCH 1/4] fix for issue #77 --- rostime/include/ros/impl/duration.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rostime/include/ros/impl/duration.h b/rostime/include/ros/impl/duration.h index 1b857d50..426c4806 100644 --- a/rostime/include/ros/impl/duration.h +++ b/rostime/include/ros/impl/duration.h @@ -56,7 +56,7 @@ namespace ros { 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)((d - (double)sec)*1000000000); + nsec = (int32_t)((d - (double)sec)*10000000000/10); return *static_cast(this); } From d84756d7623bd91ddd52dec11f4bc444c3202a98 Mon Sep 17 00:00:00 2001 From: BrutusTT Date: Thu, 22 Mar 2018 20:44:27 +0000 Subject: [PATCH 2/4] Revert "fix for issue #77" This reverts commit 2ef78cd35fbb7097992f772cbbbb689926ecf574. --- rostime/include/ros/impl/duration.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rostime/include/ros/impl/duration.h b/rostime/include/ros/impl/duration.h index 426c4806..1b857d50 100644 --- a/rostime/include/ros/impl/duration.h +++ b/rostime/include/ros/impl/duration.h @@ -56,7 +56,7 @@ namespace ros { 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)((d - (double)sec)*10000000000/10); + nsec = (int32_t)((d - (double)sec)*1000000000); return *static_cast(this); } From bfa5556ca9388fb7568187d9ed628fa687ec4287 Mon Sep 17 00:00:00 2001 From: BrutusTT Date: Thu, 22 Mar 2018 20:47:51 +0000 Subject: [PATCH 3/4] fix for issue #77 --- rostime/include/ros/impl/duration.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rostime/include/ros/impl/duration.h b/rostime/include/ros/impl/duration.h index 1b857d50..657fba99 100644 --- a/rostime/include/ros/impl/duration.h +++ b/rostime/include/ros/impl/duration.h @@ -56,7 +56,7 @@ namespace ros { 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)((d - (double)sec)*1000000000); + nsec = (int32_t)(nearbyint(d - (double)sec)*1000000000)); return *static_cast(this); } From 698436d776fe1d017655f945947ce91fce9429b9 Mon Sep 17 00:00:00 2001 From: BrutusTT Date: Thu, 22 Mar 2018 20:53:48 +0000 Subject: [PATCH 4/4] sorry, typo --- rostime/include/ros/impl/duration.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/rostime/include/ros/impl/duration.h b/rostime/include/ros/impl/duration.h index 657fba99..2ca2f5be 100644 --- a/rostime/include/ros/impl/duration.h +++ b/rostime/include/ros/impl/duration.h @@ -56,7 +56,7 @@ namespace ros { 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)); + nsec = (int32_t)(nearbyint((d - (double)sec)*1000000000)); return *static_cast(this); }