diff -Nru ros-roscpp-core-0.5.6/cpp_common/CHANGELOG.rst ros-roscpp-core-0.6.0/cpp_common/CHANGELOG.rst --- ros-roscpp-core-0.5.6/cpp_common/CHANGELOG.rst 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/cpp_common/CHANGELOG.rst 2016-03-17 21:44:05.000000000 +0000 @@ -2,6 +2,13 @@ Changelog for package cpp_common ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.6.0 (2016-03-17) +------------------ + +0.5.7 (2016-03-09) +------------------ +* export symbols for Header (`#46 `_) + 0.5.6 (2015-05-20) ------------------ diff -Nru ros-roscpp-core-0.5.6/cpp_common/include/ros/header.h ros-roscpp-core-0.6.0/cpp_common/include/ros/header.h --- ros-roscpp-core-0.5.6/cpp_common/include/ros/header.h 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/cpp_common/include/ros/header.h 2016-03-17 21:44:05.000000000 +0000 @@ -41,6 +41,7 @@ #include #include "ros/datatypes.h" +#include "cpp_common_decl.h" namespace ros { @@ -48,7 +49,7 @@ /** * \brief Provides functionality to parse a connection header and retrieve values from it */ -class Header +class CPP_COMMON_DECL Header { public: Header(); diff -Nru ros-roscpp-core-0.5.6/cpp_common/package.xml ros-roscpp-core-0.6.0/cpp_common/package.xml --- ros-roscpp-core-0.5.6/cpp_common/package.xml 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/cpp_common/package.xml 2016-03-17 21:44:05.000000000 +0000 @@ -1,6 +1,6 @@ cpp_common - 0.5.6 + 0.6.0 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 -Nru ros-roscpp-core-0.5.6/debian/changelog ros-roscpp-core-0.6.0/debian/changelog --- ros-roscpp-core-0.5.6/debian/changelog 2015-12-22 14:55:34.000000000 +0000 +++ ros-roscpp-core-0.6.0/debian/changelog 2016-07-21 09:54:10.000000000 +0000 @@ -1,4 +1,11 @@ -ros-roscpp-core (0.5.6-2~20151222) trusty; urgency=medium +ros-roscpp-core (0.6.0-1~20160721) trusty; urgency=medium + + * Imported Upstream version 0.6.0 + * Refresh patches + + -- Jochen Sprickerhof Sat, 18 Jun 2016 11:22:44 +0200 + +ros-roscpp-core (0.5.6-2) unstable; urgency=medium * Convert to new catkin with multiarch diff -Nru ros-roscpp-core-0.5.6/debian/patches/0002-Add-Debian-specific-SONAMEs.patch ros-roscpp-core-0.6.0/debian/patches/0002-Add-Debian-specific-SONAMEs.patch --- ros-roscpp-core-0.5.6/debian/patches/0002-Add-Debian-specific-SONAMEs.patch 2015-12-17 22:50:46.000000000 +0000 +++ ros-roscpp-core-0.6.0/debian/patches/0002-Add-Debian-specific-SONAMEs.patch 2016-07-21 08:31:21.000000000 +0000 @@ -33,7 +33,7 @@ install(TARGETS roscpp_serialization ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} diff --git a/rostime/CMakeLists.txt b/rostime/CMakeLists.txt -index 7ecc67f..af6b777 100644 +index c395f28..a3d3bc8 100644 --- a/rostime/CMakeLists.txt +++ b/rostime/CMakeLists.txt @@ -16,6 +16,7 @@ add_library(rostime diff -Nru ros-roscpp-core-0.5.6/roscpp_core/package.xml ros-roscpp-core-0.6.0/roscpp_core/package.xml --- ros-roscpp-core-0.5.6/roscpp_core/package.xml 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/roscpp_core/package.xml 2016-03-17 21:44:05.000000000 +0000 @@ -1,6 +1,6 @@ roscpp_core - 0.5.6 + 0.6.0 Underlying data libraries for roscpp messages. diff -Nru ros-roscpp-core-0.5.6/roscpp_serialization/CHANGELOG.rst ros-roscpp-core-0.6.0/roscpp_serialization/CHANGELOG.rst --- ros-roscpp-core-0.5.6/roscpp_serialization/CHANGELOG.rst 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/roscpp_serialization/CHANGELOG.rst 2016-03-17 21:44:05.000000000 +0000 @@ -2,6 +2,13 @@ Changelog for package roscpp_serialization ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.6.0 (2016-03-17) +------------------ + +0.5.7 (2016-03-09) +------------------ +* fix serializer bool on ARM (`#44 `_) + 0.5.6 (2015-05-20) ------------------ diff -Nru ros-roscpp-core-0.5.6/roscpp_serialization/include/ros/serialization.h ros-roscpp-core-0.6.0/roscpp_serialization/include/ros/serialization.h --- ros-roscpp-core-0.5.6/roscpp_serialization/include/ros/serialization.h 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/roscpp_serialization/include/ros/serialization.h 2016-03-17 21:44:05.000000000 +0000 @@ -243,7 +243,7 @@ { uint8_t b = (uint8_t)v; #if defined(__arm__) || defined(__arm) - memcpy(stream.advance(sizeof(1)), &b, 1 ); + memcpy(stream.advance(1), &b, 1 ); #else *reinterpret_cast(stream.advance(1)) = b; #endif @@ -253,7 +253,7 @@ { uint8_t b; #if defined(__arm__) || defined(__arm) - memcpy(&b, stream.advance(sizeof(1)), 1 ); + memcpy(&b, stream.advance(1), 1 ); #else b = *reinterpret_cast(stream.advance(1)); #endif diff -Nru ros-roscpp-core-0.5.6/roscpp_serialization/package.xml ros-roscpp-core-0.6.0/roscpp_serialization/package.xml --- ros-roscpp-core-0.5.6/roscpp_serialization/package.xml 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/roscpp_serialization/package.xml 2016-03-17 21:44:05.000000000 +0000 @@ -1,6 +1,6 @@ roscpp_serialization - 0.5.6 + 0.6.0 roscpp_serialization contains the code for serialization as described in MessagesSerializationAndAdaptingTypes. diff -Nru ros-roscpp-core-0.5.6/roscpp_traits/CHANGELOG.rst ros-roscpp-core-0.6.0/roscpp_traits/CHANGELOG.rst --- ros-roscpp-core-0.5.6/roscpp_traits/CHANGELOG.rst 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/roscpp_traits/CHANGELOG.rst 2016-03-17 21:44:05.000000000 +0000 @@ -2,6 +2,12 @@ Changelog for package roscpp_traits ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.6.0 (2016-03-17) +------------------ + +0.5.7 (2016-03-09) +------------------ + 0.5.6 (2015-05-20) ------------------ * fix for compile issue on OS X 10.10 (`#34 `_) diff -Nru ros-roscpp-core-0.5.6/roscpp_traits/include/ros/message_traits.h ros-roscpp-core-0.6.0/roscpp_traits/include/ros/message_traits.h --- ros-roscpp-core-0.5.6/roscpp_traits/include/ros/message_traits.h 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/roscpp_traits/include/ros/message_traits.h 2016-03-17 21:44:05.000000000 +0000 @@ -168,8 +168,8 @@ template struct Header { - static std_msgs::Header* pointer(M& m) { return 0; } - static std_msgs::Header const* pointer(const M& m) { return 0; } + static std_msgs::Header* pointer(M& m) { (void)m; return 0; } + static std_msgs::Header const* pointer(const M& m) { (void)m; return 0; } }; template @@ -187,8 +187,8 @@ template struct FrameId { - static std::string* pointer(M& m) { return 0; } - static std::string const* pointer(const M& m) { return 0; } + static std::string* pointer(M& m) { (void)m; return 0; } + static std::string const* pointer(const M& m) { (void)m; return 0; } }; template @@ -207,8 +207,8 @@ template struct TimeStamp { - static ros::Time* pointer(M& m) { return 0; } - static ros::Time const* pointer(const M& m) { return 0; } + static ros::Time* pointer(M& m) { (void)m; return 0; } + static ros::Time const* pointer(const M& m) { (void)m; return 0; } }; template diff -Nru ros-roscpp-core-0.5.6/roscpp_traits/package.xml ros-roscpp-core-0.6.0/roscpp_traits/package.xml --- ros-roscpp-core-0.5.6/roscpp_traits/package.xml 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/roscpp_traits/package.xml 2016-03-17 21:44:05.000000000 +0000 @@ -1,6 +1,6 @@ roscpp_traits - 0.5.6 + 0.6.0 roscpp_traits contains the message traits code as described in MessagesTraits. diff -Nru ros-roscpp-core-0.5.6/rostime/CHANGELOG.rst ros-roscpp-core-0.6.0/rostime/CHANGELOG.rst --- ros-roscpp-core-0.5.6/rostime/CHANGELOG.rst 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/rostime/CHANGELOG.rst 2016-03-17 21:44:05.000000000 +0000 @@ -2,6 +2,15 @@ Changelog for package rostime ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +0.6.0 (2016-03-17) +------------------ +* change Duration:sleep return semantic (`#47 `_) + +0.5.7 (2016-03-09) +------------------ +* Adjust return value of sleep() function (`#45 `_) +* fix WallRate(Duration) constructor (`#40 `_) + 0.5.6 (2015-05-20) ------------------ diff -Nru ros-roscpp-core-0.5.6/rostime/CMakeLists.txt ros-roscpp-core-0.6.0/rostime/CMakeLists.txt --- ros-roscpp-core-0.5.6/rostime/CMakeLists.txt 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/rostime/CMakeLists.txt 2016-03-17 21:44:05.000000000 +0000 @@ -32,6 +32,10 @@ FILES_MATCHING PATTERN "*.h") if(CATKIN_ENABLE_TESTING) + catkin_add_gtest(${PROJECT_NAME}-test_duration test/duration.cpp) + if(TARGET ${PROJECT_NAME}-test_duration) + target_link_libraries(${PROJECT_NAME}-test_duration ${catkin_LIBRARIES} rostime) + endif() catkin_add_gtest(${PROJECT_NAME}-test_time test/time.cpp) if(TARGET ${PROJECT_NAME}-test_time) target_link_libraries(${PROJECT_NAME}-test_time ${catkin_LIBRARIES} rostime) diff -Nru ros-roscpp-core-0.5.6/rostime/include/ros/duration.h ros-roscpp-core-0.6.0/rostime/include/ros/duration.h --- ros-roscpp-core-0.5.6/rostime/include/ros/duration.h 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/rostime/include/ros/duration.h 2016-03-17 21:44:05.000000000 +0000 @@ -120,6 +120,7 @@ explicit Duration(const Rate&); /** * \brief sleep for the amount of time specified by this Duration. If a signal interrupts the sleep, resleeps for the time remaining. + * @return True if the desired sleep duration was met, false otherwise. */ bool sleep() const; }; @@ -147,6 +148,7 @@ explicit WallDuration(const Rate&); /** * \brief sleep for the amount of time specified by this Duration. If a signal interrupts the sleep, resleeps for the time remaining. + * @return True if the desired sleep duration was met, false otherwise. */ bool sleep() const; }; diff -Nru ros-roscpp-core-0.5.6/rostime/include/ros/rate.h ros-roscpp-core-0.6.0/rostime/include/ros/rate.h --- ros-roscpp-core-0.5.6/rostime/include/ros/rate.h 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/rostime/include/ros/rate.h 2016-03-17 21:44:05.000000000 +0000 @@ -101,7 +101,7 @@ /** * @brief Sleeps for any leftover time in a cycle. Calculated from the last time sleep, reset, or the constructor was called. - * @return Passes through the return value from WallDuration::sleep() if it slept, otherwise True + * @return Passes through the return value from WallDuration::sleep() if it slept, false otherwise. */ bool sleep(); diff -Nru ros-roscpp-core-0.5.6/rostime/include/ros/time.h ros-roscpp-core-0.6.0/rostime/include/ros/time.h --- ros-roscpp-core-0.5.6/rostime/include/ros/time.h 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/rostime/include/ros/time.h 2016-03-17 21:44:05.000000000 +0000 @@ -186,6 +186,7 @@ static Time now(); /** * \brief Sleep until a specific time has been reached. + * @return True if the desired sleep time was met, false otherwise. */ static bool sleepUntil(const Time& end); @@ -241,6 +242,7 @@ /** * \brief Sleep until a specific time has been reached. + * @return True if the desired sleep time was met, false otherwise. */ static bool sleepUntil(const WallTime& end); diff -Nru ros-roscpp-core-0.5.6/rostime/package.xml ros-roscpp-core-0.6.0/rostime/package.xml --- ros-roscpp-core-0.5.6/rostime/package.xml 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/rostime/package.xml 2016-03-17 21:44:05.000000000 +0000 @@ -1,6 +1,6 @@ rostime - 0.5.6 + 0.6.0 Time and Duration implementations for C++ libraries, including roscpp. diff -Nru ros-roscpp-core-0.5.6/rostime/src/rate.cpp ros-roscpp-core-0.6.0/rostime/src/rate.cpp --- ros-roscpp-core-0.5.6/rostime/src/rate.cpp 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/rostime/src/rate.cpp 2016-03-17 21:44:05.000000000 +0000 @@ -83,7 +83,8 @@ { start_ = actual_end; } - return true; + // return false to show that the desired rate was not met + return false; } return sleep_time.sleep(); @@ -107,7 +108,7 @@ WallRate::WallRate(const Duration& d) : start_(WallTime::now()) -, expected_cycle_time_(1.0 / d.toSec()) +, expected_cycle_time_(d.sec, d.nsec) , actual_cycle_time_(0.0) {} @@ -141,7 +142,7 @@ { start_ = actual_end; } - return true; + return false; } return sleep_time.sleep(); diff -Nru ros-roscpp-core-0.5.6/rostime/src/time.cpp ros-roscpp-core-0.6.0/rostime/src/time.cpp --- ros-roscpp-core-0.5.6/rostime/src/time.cpp 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/rostime/src/time.cpp 2016-03-17 21:44:05.000000000 +0000 @@ -404,9 +404,11 @@ end = TIME_MAX; } + bool rc = false; while (!g_stopped && (Time::now() < end)) { ros_wallsleep(0, 1000000); + rc = true; // If we started at time 0 wait for the first actual time to arrive before starting the timer on // our sleep @@ -423,7 +425,7 @@ } } - return true; + return rc && !g_stopped; } } diff -Nru ros-roscpp-core-0.5.6/rostime/test/duration.cpp ros-roscpp-core-0.6.0/rostime/test/duration.cpp --- ros-roscpp-core-0.5.6/rostime/test/duration.cpp 1970-01-01 00:00:00.000000000 +0000 +++ ros-roscpp-core-0.6.0/rostime/test/duration.cpp 2016-03-17 21:44:05.000000000 +0000 @@ -0,0 +1,54 @@ +/* + * Copyright (c) 2016, Open Source Robotics Foundation, Inc.. + * All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions are met: + * + * * Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * * Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in the + * documentation and/or other materials provided with the distribution. + * * Neither the name of Willow Garage, Inc. nor the names of its + * contributors may be used to endorse or promote products derived from + * this software without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE + * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE + * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR + * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF + * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS + * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN + * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) + * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + */ + +#include +#include +#include + +using namespace ros; + +TEST(Duration, sleepWithSimTime) +{ + ros::Time::init(); + + Time start = Time::now(); + start -= Duration(2.0); + Time::setNow(start); + + Time::shutdown(); + + Duration d(1.0); + bool rc = d.sleep(); + ASSERT_FALSE(rc); +} + +int main(int argc, char **argv){ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} diff -Nru ros-roscpp-core-0.5.6/rostime/test/time.cpp ros-roscpp-core-0.6.0/rostime/test/time.cpp --- ros-roscpp-core-0.5.6/rostime/test/time.cpp 2015-05-20 23:56:11.000000000 +0000 +++ ros-roscpp-core-0.6.0/rostime/test/time.cpp 2016-03-17 21:44:05.000000000 +0000 @@ -428,10 +428,11 @@ alarm(1); Time start = Time::now(); Duration d(2.0); - d.sleep(); + bool rc = d.sleep(); Time end = Time::now(); ASSERT_GT(end - start, d); + ASSERT_TRUE(rc); } TEST(Rate, constructFromDuration){ @@ -440,6 +441,25 @@ EXPECT_EQ(r.expectedCycleTime(), d); } +TEST(Rate, sleep_return_value_true){ + Rate r(Duration(0.2)); + Duration(r.expectedCycleTime() * 0.5).sleep(); + EXPECT_TRUE(r.sleep()); +} + +TEST(Rate, sleep_return_value_false){ + Rate r(Duration(0.2)); + Duration(r.expectedCycleTime() * 2).sleep(); + EXPECT_FALSE(r.sleep()); // requested rate cannot be achieved +} + +TEST(WallRate, constructFromDuration){ + Duration d(4, 0); + WallRate r(d); + WallDuration wd(4, 0); + EXPECT_EQ(r.expectedCycleTime(), wd); +} + /////////////////////////////////////////////////////////////////////////////////// // WallTime/WallDuration ///////////////////////////////////////////////////////////////////////////////////