[roscpp-core] 01/01: Imported Upstream version 0.5.5

Jochen Sprickerhof jspricke-guest at moszumanska.debian.org
Fri Jan 16 10:23:32 UTC 2015


This is an automated email from the git hooks/post-receive script.

jspricke-guest pushed a commit to annotated tag upstream/0.5.5
in repository roscpp-core.

commit 3c4bd95a652ebb3b5b806cf3dccd92f15809ca61
Author: Jochen Sprickerhof <git at jochen.sprickerhof.de>
Date:   Wed Jan 14 11:27:19 2015 +0100

    Imported Upstream version 0.5.5
---
 cpp_common/CHANGELOG.rst            |  3 +++
 cpp_common/package.xml              |  2 +-
 roscpp_core/package.xml             |  2 +-
 roscpp_serialization/CHANGELOG.rst  |  3 +++
 roscpp_serialization/package.xml    |  2 +-
 roscpp_traits/CHANGELOG.rst         |  3 +++
 roscpp_traits/package.xml           |  2 +-
 rostime/CHANGELOG.rst               |  5 +++++
 rostime/include/ros/impl/duration.h | 21 +-----------------
 rostime/package.xml                 |  2 +-
 rostime/src/duration.cpp            |  8 +++++++
 rostime/test/time.cpp               | 44 ++++++++++++++++++++++++++++---------
 12 files changed, 62 insertions(+), 35 deletions(-)

diff --git a/cpp_common/CHANGELOG.rst b/cpp_common/CHANGELOG.rst
index fe12ff0..32fcc4b 100644
--- a/cpp_common/CHANGELOG.rst
+++ b/cpp_common/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package cpp_common
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+0.5.5 (2014-12-22)
+------------------
+
 0.5.4 (2014-07-23)
 ------------------
 
diff --git a/cpp_common/package.xml b/cpp_common/package.xml
index a364080..723ac33 100644
--- a/cpp_common/package.xml
+++ b/cpp_common/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>cpp_common</name>
-  <version>0.5.4</version>
+  <version>0.5.5</version>
   <description>
     cpp_common contains C++ code for doing things that are not necessarily ROS
     related, but are useful for multiple packages. This includes things like
diff --git a/roscpp_core/package.xml b/roscpp_core/package.xml
index c919d63..307280e 100644
--- a/roscpp_core/package.xml
+++ b/roscpp_core/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>roscpp_core</name>
-  <version>0.5.4</version>
+  <version>0.5.5</version>
   <description>
     Underlying data libraries for roscpp messages.
   </description>
diff --git a/roscpp_serialization/CHANGELOG.rst b/roscpp_serialization/CHANGELOG.rst
index e0aee1e..e0f26ff 100644
--- a/roscpp_serialization/CHANGELOG.rst
+++ b/roscpp_serialization/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package roscpp_serialization
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+0.5.5 (2014-12-22)
+------------------
+
 0.5.4 (2014-07-23)
 ------------------
 
diff --git a/roscpp_serialization/package.xml b/roscpp_serialization/package.xml
index 8aaa837..9541036 100644
--- a/roscpp_serialization/package.xml
+++ b/roscpp_serialization/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>roscpp_serialization</name>
-  <version>0.5.4</version>
+  <version>0.5.5</version>
   <description>
     roscpp_serialization contains the code for serialization as described in
     <a href="http://www.ros.org/wiki/roscpp/Overview/MessagesSerializationAndAdaptingTypes">MessagesSerializationAndAdaptingTypes</a>.
diff --git a/roscpp_traits/CHANGELOG.rst b/roscpp_traits/CHANGELOG.rst
index c4e4a25..737bc50 100644
--- a/roscpp_traits/CHANGELOG.rst
+++ b/roscpp_traits/CHANGELOG.rst
@@ -2,6 +2,9 @@
 Changelog for package roscpp_traits
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+0.5.5 (2014-12-22)
+------------------
+
 0.5.4 (2014-07-23)
 ------------------
 
diff --git a/roscpp_traits/package.xml b/roscpp_traits/package.xml
index c9a7c05..6c29326 100644
--- a/roscpp_traits/package.xml
+++ b/roscpp_traits/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>roscpp_traits</name>
-  <version>0.5.4</version>
+  <version>0.5.5</version>
   <description>
     roscpp_traits contains the message traits code as described in
     <a href="http://www.ros.org/wiki/roscpp/Overview/MessagesTraits">MessagesTraits</a>.
diff --git a/rostime/CHANGELOG.rst b/rostime/CHANGELOG.rst
index 0836e27..8468368 100644
--- a/rostime/CHANGELOG.rst
+++ b/rostime/CHANGELOG.rst
@@ -2,6 +2,11 @@
 Changelog for package rostime
 ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
 
+0.5.5 (2014-12-22)
+------------------
+* move implementation of Duration(Rate) constructor (`#30 <https://github.com/ros/roscpp_core/issues/30>`_)
+* fix Duration initialization from seconds for negative values  (`#29 <https://github.com/ros/roscpp_core/pull/29>`_)
+
 0.5.4 (2014-07-23)
 ------------------
 * fix Rate initialized by Duration (`#26 <https://github.com/ros/roscpp_core/issues/26>`_)
diff --git a/rostime/include/ros/impl/duration.h b/rostime/include/ros/impl/duration.h
index 687705f..371064f 100644
--- a/rostime/include/ros/impl/duration.h
+++ b/rostime/include/ros/impl/duration.h
@@ -52,16 +52,7 @@ namespace ros {
   template<class T>
   T& DurationBase<T>::fromSec(double d)
   {
-#ifdef HAVE_TRUNC
-    sec  = (int32_t)trunc(d);
-#else
-    // (morgan: why doesn't win32 provide trunc? argh. hacked this together
-    // without much thought. need to test this conversion.
-    if (d >= 0.0)
-      sec = (int32_t)floor(d);
-    else
-      sec = (int32_t)floor(d) + 1;
-#endif
+    sec = (int32_t)floor(d);
     nsec = (int32_t)((d - (double)sec)*1000000000);
     return *static_cast<T*>(this);
   }
@@ -185,15 +176,5 @@ namespace ros {
     return bt::seconds(sec) + bt::microseconds(nsec/1000.0);
 #endif
   }
-
-  inline Duration::Duration(const Rate& r)
-  {
-    fromSec(r.expectedCycleTime().toSec());
-  }
-
-  inline WallDuration::WallDuration(const Rate& r)
-  {
-    fromSec(r.expectedCycleTime().toSec());
-  }
 }
 #endif
diff --git a/rostime/package.xml b/rostime/package.xml
index 8a46b43..96439a1 100644
--- a/rostime/package.xml
+++ b/rostime/package.xml
@@ -1,6 +1,6 @@
 <package>
   <name>rostime</name>
-  <version>0.5.4</version>
+  <version>0.5.5</version>
   <description>
     Time and Duration implementations for C++ libraries, including roscpp.
   </description>
diff --git a/rostime/src/duration.cpp b/rostime/src/duration.cpp
index e2e8ca6..72857c6 100644
--- a/rostime/src/duration.cpp
+++ b/rostime/src/duration.cpp
@@ -36,6 +36,14 @@
 
 namespace ros {
 
+  Duration::Duration(const Rate& rate)
+    : DurationBase<Duration>(rate.expectedCycleTime().sec, rate.expectedCycleTime().nsec)
+  { }
+
+  WallDuration::WallDuration(const Rate& rate)
+    : DurationBase<WallDuration>(rate.expectedCycleTime().sec, rate.expectedCycleTime().nsec)
+  { }
+
   void normalizeSecNSecSigned(int64_t& sec, int64_t& nsec)
   {
     int64_t nsec_part = nsec % 1000000000L;
diff --git a/rostime/test/time.cpp b/rostime/test/time.cpp
index 95be573..3ded4d8 100644
--- a/rostime/test/time.cpp
+++ b/rostime/test/time.cpp
@@ -69,12 +69,33 @@ void generate_rand_durations(uint32_t range, uint64_t runs, std::vector<ros::Dur
   seed_rand();
   values1.clear();
   values2.clear();
-  values1.reserve(runs);
-  values2.reserve(runs);
+  values1.reserve(runs * 4);
+  values2.reserve(runs * 4);
   for ( uint32_t i = 0; i < runs ; i++ )
   {
-    values1.push_back(ros::Duration( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
-    values2.push_back(ros::Duration( (rand() * range / RAND_MAX), (rand() * 1000000000ULL/RAND_MAX)));
+    // positive durations
+    values1.push_back(ros::Duration(  (rand() * range / RAND_MAX),  (rand() * 1000000000ULL/RAND_MAX)));
+    values2.push_back(ros::Duration(  (rand() * range / RAND_MAX),  (rand() * 1000000000ULL/RAND_MAX)));
+    EXPECT_GE(values1.back(), ros::Duration(0,0));
+    EXPECT_GE(values2.back(), ros::Duration(0,0));
+
+    // negative durations
+    values1.push_back(ros::Duration( -(rand() * range / RAND_MAX), -(rand() * 1000000000ULL/RAND_MAX)));
+    values2.push_back(ros::Duration( -(rand() * range / RAND_MAX), -(rand() * 1000000000ULL/RAND_MAX)));
+    EXPECT_LE(values1.back(), ros::Duration(0,0));
+    EXPECT_LE(values2.back(), ros::Duration(0,0));
+
+    // positive and negative durations
+    values1.push_back(ros::Duration(  (rand() * range / RAND_MAX),  (rand() * 1000000000ULL/RAND_MAX)));
+    values2.push_back(ros::Duration( -(rand() * range / RAND_MAX), -(rand() * 1000000000ULL/RAND_MAX)));
+    EXPECT_GE(values1.back(), ros::Duration(0,0));
+    EXPECT_LE(values2.back(), ros::Duration(0,0));
+
+    // negative and positive durations
+    values1.push_back(ros::Duration( -(rand() * range / RAND_MAX), -(rand() * 1000000000ULL/RAND_MAX)));
+    values2.push_back(ros::Duration(  (rand() * range / RAND_MAX),  (rand() * 1000000000ULL/RAND_MAX)));
+    EXPECT_LE(values1.back(), ros::Duration(0,0));
+    EXPECT_GE(values2.back(), ros::Duration(0,0));
   }
 }
 
@@ -261,17 +282,19 @@ TEST(Duration, Comparitors)
 
   for (uint32_t i = 0; i < v1.size(); i++)
   {
-    if (v1[i].sec * 1000000000ULL + v1[i].nsec < v2[i].sec * 1000000000ULL + v2[i].nsec)
+    if (v1[i].sec * 1000000000LL + v1[i].nsec < v2[i].sec * 1000000000LL + v2[i].nsec)
     {
       EXPECT_LT(v1[i], v2[i]);
-      //      printf("%f %d ", v1[i].toSec(), v1[i].sec * 1000000000ULL + v1[i].nsec);
-      //printf("vs %f %d\n", v2[i].toSec(), v2[i].sec * 1000000000ULL + v2[i].nsec);
+//      printf("%f %lld ", v1[i].toSec(), v1[i].sec * 1000000000LL + v1[i].nsec);
+//      printf("vs %f %lld\n", v2[i].toSec(), v2[i].sec * 1000000000LL + v2[i].nsec);
       EXPECT_LE(v1[i], v2[i]);
       EXPECT_NE(v1[i], v2[i]);
     }
-    else if (v1[i].sec * 1000000000ULL + v1[i].nsec > v2[i].sec * 1000000000ULL + v2[i].nsec)
+    else if (v1[i].sec * 1000000000LL + v1[i].nsec > v2[i].sec * 1000000000LL + v2[i].nsec)
     {
       EXPECT_GT(v1[i], v2[i]);
+//      printf("%f %lld ", v1[i].toSec(), v1[i].sec * 1000000000LL + v1[i].nsec);
+//      printf("vs %f %lld\n", v2[i].toSec(), v2[i].sec * 1000000000LL + v2[i].nsec);
       EXPECT_GE(v1[i], v2[i]);
       EXPECT_NE(v1[i], v2[i]);
     }
@@ -283,7 +306,6 @@ TEST(Duration, Comparitors)
     }
 
   }
-
 }
 
 TEST(Duration, ToFromSec)
@@ -295,9 +317,11 @@ TEST(Duration, ToFromSec)
   for (uint32_t i = 0; i < v1.size(); i++)
   {
     EXPECT_EQ(v1[i].toSec(), v1[i].fromSec(v1[i].toSec()).toSec());
-
+    EXPECT_GE(ros::Duration(v1[i].toSec()).nsec, 0);
   }
 
+  EXPECT_EQ(ros::Duration(-0.5), ros::Duration(-1LL, 500000000LL));
+  EXPECT_EQ(ros::Duration(-0.5), ros::Duration(0, -500000000LL));
 }
 
 

-- 
Alioth's /usr/local/bin/git-commit-notice on /srv/git.debian.org/git/debian-science/packages/ros/roscpp-core.git



More information about the debian-science-commits mailing list