Skip to content

Commit

Permalink
Drop custom implementation of boost::condition_variable to fix busy-w…
Browse files Browse the repository at this point in the history
…ait spinning (ros#1878)

* roscpp: fix potential busy-wait loop caused by backported Boost condition_variable (fix ros#1343)

ros#1014 and ros#1250 introduced a backported
version of boost::condition_variable, where support for steady (monotonic) clocks has been added in version 1.61.
But the namespace of the backported version was not changed and the symbol names might clash with the original
version.

Because the underlying clock used for the condition_variable is set in the constructor and must be
consistent with the the expectations within member variables. The compiler might choose to inline one or the
other or both, and is more likely to do so for optimized Release builds. But if it does not, the symbol ends
up in the symbol table of roscpp and depending on which other libraries will be linked into the process it
is unpredictable which of the two versions will be actually called at the end. In case the constructor defined
in `/usr/include/boost/thread/pthread/condition_variable.hpp` was called and did not configure the internal
pthread condition variable for monotonic clock, each call to the backported do_wait_until() method with a
monotonic timestamp will return immediately and hence causes `CallbackQueue::callOne(timeout)` or
`CallbackQueue::callAvailable(timeout)` to return immediately.

This patch changes the namespace of the backported condition_variable implementation to boost_161. This
removes the ambiguity with the original definition if both are used in the same process.

* roscpp: use boost::condition_variable::wait_for() instead of deprecated timed_wait()

This fixes ROS timers in combination with 2c18b9f. The timer
callbacks were not called because the TimerManager's thread function blocked indefinitely on
boost::condition_variable::timed_wait().

Relative timed_wait() uses the system clock (boost::get_system_time()) unconditionally to
calculate the absolute timestamp for do_wait_until(). If the condition variable has been
initialized with BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC, it compares this timestamp
with the monotonic clock and therefore blocks.

This issue has been reported in https://svn.boost.org/trac10/ticket/12728 and will not be
fixed. The timed_wait interface is apparently deprecated.

* roscpp: do not use boost_161_condition_variable.h on Windows (untested)

* roscpp: remove specialized implementation of TimerManager<T,D,E>::threadFunc() in steady_timer.cpp

The updated generic definition in timer_manager.h should do the same with a minor update.
In all cases we can call boost::condition_variable::wait_until() with an absolute time_point of the respective clock.
The conversion from system_clock to steady_clock for Time and WallTime is done internally in
boost::condition_variable::wait_until(lock_type& lock, const chrono::time_point<Clock, Duration>& t).

* fix namespaces

* add more explicit namespaces

* add missing ns

* roscpp: fixed Boost version check in CMakeLists.txt

find_package(Boost) has to come before checking the Boost version.
Otherwise BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC was not defined which
triggered the assertion in timer_manager.h:240.

Since Boost 1.67 BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC became the default
if the platform supports it and the macro is not defined anymore. Instead, check
for BOOST_THREAD_INTERNAL_CLOCK_IS_MONO.

* roscpp: replace ROSCPP_BOOST_CONDITION_VARIABLE and ROSCPP_BOOST_CONDITION_VARIABLE_HEADER macros by a typedef in internal_condition_variable.h

* Remove copy of boost::condition_variable implementation from Boost 1.61 in namespace boost_161

* Revert some changes in include directives and in CMakeLists.txt to minimize the diff to melodic-devel

Addresses ros#1878 (review).

* use wait_for(), remove TimerManagerTraits

* Revert "use wait_for(), remove TimerManagerTraits"

This reverts commit 2a67cf6.

Co-authored-by: Antoine Hoarau <703240+ahoarau@users.noreply.github.com>
Co-authored-by: Dirk Thomas <dirk-thomas@users.noreply.github.com>
  • Loading branch information
3 people committed Jul 31, 2020
1 parent 53ab192 commit 8f9bd84
Show file tree
Hide file tree
Showing 11 changed files with 42 additions and 973 deletions.
12 changes: 12 additions & 0 deletions clients/roscpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,18 @@ configure_file(${CMAKE_CURRENT_SOURCE_DIR}/include/ros/common.h.in ${CATKIN_DEVE

find_package(Boost REQUIRED COMPONENTS chrono filesystem signals system)

# Make sure we use CLOCK_MONOTONIC for the condition variable wait_for if not Apple.
if(NOT APPLE AND NOT WIN32)
if(Boost_VERSION LESS 106100)
message(FATAL_ERROR "${PROJECT_NAME} requires Boost 1.61 or above.")
endif()
if(Boost_VERSION LESS 106700)
# CLOCK_MONOTONIC became the default in Boost 1.67:
# https://github.com/boostorg/thread/commit/1e84b978b2bb0aae830cc14533dea3b7ddda5cde
add_definitions(-DBOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC)
endif()
endif()

include_directories(include ${CATKIN_DEVEL_PREFIX}/${CATKIN_GLOBAL_INCLUDE_DESTINATION}/ros ${catkin_INCLUDE_DIRS} ${Boost_INCLUDE_DIRS})

add_message_files(
Expand Down
23 changes: 0 additions & 23 deletions clients/roscpp/include/boost_161_condition_variable.h

This file was deleted.

Loading

0 comments on commit 8f9bd84

Please sign in to comment.