Skip to content

Commit

Permalink
Use an internal implementation of boost::condition_variable with mono…
Browse files Browse the repository at this point in the history
…tonic clock (#1932)

* Use an internal implementation of condition_variable with monotonic clock to avoid ODR violation

* Fix build of ros/internal/condition_variable.h for Boost <1.65

* Fix "static_assert with no message is a C++17 extension" warning in ros/internal/condition_variable.h
  • Loading branch information
meyerj authored Jul 28, 2020
1 parent f11086c commit f781def
Show file tree
Hide file tree
Showing 7 changed files with 233 additions and 30 deletions.
12 changes: 0 additions & 12 deletions clients/roscpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,18 +24,6 @@ configure_file(${CMAKE_CURRENT_SOURCE_DIR}/include/ros/common.h.in ${CATKIN_DEVE

find_package(Boost REQUIRED COMPONENTS chrono filesystem 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})
# this is needed for use within a bazel workspace. See #1548 for details.
include_directories(${CATKIN_DEVEL_PREFIX}/${CATKIN_GLOBAL_INCLUDE_DESTINATION})
Expand Down
4 changes: 2 additions & 2 deletions clients/roscpp/include/ros/callback_queue.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,11 +36,11 @@
#define ROSCPP_CALLBACK_QUEUE_H

#include "ros/callback_queue_interface.h"
#include "ros/internal/condition_variable.h"
#include "ros/time.h"
#include "common.h"

#include <boost/shared_ptr.hpp>
#include <boost/thread/condition_variable.hpp>
#include <boost/thread/mutex.hpp>
#include <boost/thread/shared_mutex.hpp>
#include <boost/thread/tss.hpp>
Expand Down Expand Up @@ -163,7 +163,7 @@ class ROSCPP_DECL CallbackQueue : public CallbackQueueInterface
D_CallbackInfo callbacks_;
size_t calling_;
boost::mutex mutex_;
boost::condition_variable condition_;
ros::internal::condition_variable_monotonic condition_;

boost::mutex id_info_mutex_;
M_IDInfo id_info_;
Expand Down
221 changes: 221 additions & 0 deletions clients/roscpp/include/ros/internal/condition_variable.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,221 @@
/*
* Copyright (C) 2020, Willow Garage, Inc.
*
* 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 names of Stanford University or 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.
*/

// Distributed under the Boost Software License, Version 1.0. (See
// accompanying file LICENSE_1_0.txt or copy at
// http://www.boost.org/LICENSE_1_0.txt)
// (C) Copyright 2007-10 Anthony Williams
// (C) Copyright 2011-2012 Vicente J. Botet Escriba

#ifndef ROSCPP_INTERNAL_CONDITION_VARIABLE_H
#define ROSCPP_INTERNAL_CONDITION_VARIABLE_H

#include <boost/thread/condition_variable.hpp>

namespace ros {
namespace internal {

#if !defined(BOOST_THREAD_PLATFORM_PTHREAD) || \
defined(BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC) || \
defined(BOOST_THREAD_INTERNAL_CLOCK_IS_MONO)
using condition_variable_monotonic = boost::condition_variable;

#else

class condition_variable_monotonic {
private:
#if defined BOOST_THREAD_PROVIDES_INTERRUPTIONS
pthread_mutex_t internal_mutex;
#endif
pthread_cond_t cond;

public:
condition_variable_monotonic() {
int res;
#if defined BOOST_THREAD_PROVIDES_INTERRUPTIONS
res = pthread_mutex_init(&internal_mutex, NULL);
if (res)
{
boost::throw_exception(boost::thread_resource_error(res, "ros::internal::condition_variable_monotonic::condition_variable_monotonic() constructor failed in pthread_mutex_init"));
}
#endif

// res = boost::detail::monotonic_pthread_cond_init(cond);
pthread_condattr_t attr;
res = pthread_condattr_init(&attr);
if (res == 0) {
pthread_condattr_setclock(&attr, CLOCK_MONOTONIC);
res = pthread_cond_init(&cond, &attr);
pthread_condattr_destroy(&attr);
}

if (res)
{
#if defined BOOST_THREAD_PROVIDES_INTERRUPTIONS
BOOST_VERIFY(!pthread_mutex_destroy(&internal_mutex));
#endif
boost::throw_exception(boost::thread_resource_error(res, "ros::internal::condition_variable_monotonic::condition_variable() constructor failed in detail::monotonic_pthread_cond_init"));
}
}

void notify_one() BOOST_NOEXCEPT
{
#if defined BOOST_THREAD_PROVIDES_INTERRUPTIONS
boost::pthread::pthread_mutex_scoped_lock internal_lock(&internal_mutex);
#endif
BOOST_VERIFY(!pthread_cond_signal(&cond));
}

void notify_all() BOOST_NOEXCEPT
{
#if defined BOOST_THREAD_PROVIDES_INTERRUPTIONS
boost::pthread::pthread_mutex_scoped_lock internal_lock(&internal_mutex);
#endif
BOOST_VERIFY(!pthread_cond_broadcast(&cond));
}

template <class Duration>
boost::cv_status wait_until(
boost::unique_lock<boost::mutex> &lock,
const boost::chrono::time_point<boost::chrono::steady_clock, Duration> &t)
{
using namespace boost::chrono;
typedef time_point<steady_clock, nanoseconds> nano_sys_tmpt;
wait_until(lock,
nano_sys_tmpt(ceil<nanoseconds>(t.time_since_epoch())));
return steady_clock::now() < t ? boost::cv_status::no_timeout : boost::cv_status::timeout;
}

template <class Clock, class Duration>
boost::cv_status wait_until(
boost::unique_lock<boost::mutex> &lock,
const boost::chrono::time_point<Clock, Duration> &t)
{
using namespace boost::chrono;
steady_clock::time_point s_now = steady_clock::now();
typename Clock::time_point c_now = Clock::now();
wait_until(lock, s_now + ceil<nanoseconds>(t - c_now));
return Clock::now() < t ? boost::cv_status::no_timeout : boost::cv_status::timeout;
}

template <class Rep, class Period>
boost::cv_status wait_for(
boost::unique_lock<boost::mutex> &lock,
const boost::chrono::duration<Rep, Period> &d)
{
using namespace boost::chrono;
steady_clock::time_point c_now = steady_clock::now();
wait_until(lock, c_now + ceil<nanoseconds>(d));
return steady_clock::now() - c_now < d ? boost::cv_status::no_timeout : boost::cv_status::timeout;
}

boost::cv_status wait_until(
boost::unique_lock<boost::mutex> &lk,
boost::chrono::time_point<boost::chrono::steady_clock, boost::chrono::nanoseconds> tp)
{
using namespace boost::chrono;
nanoseconds d = tp.time_since_epoch();
timespec ts = boost::detail::to_timespec(d);
if (do_wait_until(lk, ts))
return boost::cv_status::no_timeout;
else
return boost::cv_status::timeout;
}

void wait(boost::unique_lock<boost::mutex> &m)
{
int res = 0;
{
#if defined BOOST_THREAD_PROVIDES_INTERRUPTIONS
boost::thread_cv_detail::lock_on_exit<boost::unique_lock<boost::mutex>> guard;
boost::detail::interruption_checker check_for_interruption(&internal_mutex, &cond);
pthread_mutex_t *the_mutex = &internal_mutex;
guard.activate(m);
res = pthread_cond_wait(&cond, the_mutex);
#if BOOST_VERSION >= 106500
check_for_interruption.check();
guard.deactivate();
#endif
#else
pthread_mutex_t *the_mutex = m.mutex()->native_handle();
res = pthread_cond_wait(&cond, the_mutex);
#endif
}
#if defined BOOST_THREAD_PROVIDES_INTERRUPTIONS
boost::this_thread::interruption_point();
#endif
if (res && res != EINTR)
{
boost::throw_exception(boost::condition_error(res, "ros::internal::condition_variable_monotonic::wait failed in pthread_cond_wait"));
}
}

bool do_wait_until(
boost::unique_lock<boost::mutex> &m,
struct timespec const &timeout)
{
int cond_res;
{
#if defined BOOST_THREAD_PROVIDES_INTERRUPTIONS
boost::thread_cv_detail::lock_on_exit<boost::unique_lock<boost::mutex>> guard;
boost::detail::interruption_checker check_for_interruption(&internal_mutex, &cond);
pthread_mutex_t *the_mutex = &internal_mutex;
guard.activate(m);
cond_res = pthread_cond_timedwait(&cond, the_mutex, &timeout);
#if BOOST_VERSION >= 106500
check_for_interruption.check();
guard.deactivate();
#endif
#else
pthread_mutex_t *the_mutex = m.mutex()->native_handle();
cond_res = pthread_cond_timedwait(&cond, the_mutex, &timeout);
#endif
}
#if defined BOOST_THREAD_PROVIDES_INTERRUPTIONS
boost::this_thread::interruption_point();
#endif
if (cond_res == ETIMEDOUT)
{
return false;
}
if (cond_res)
{
boost::throw_exception(boost::condition_error(cond_res, "ros::internal::condition_variable_monotonic::do_wait_until failed in pthread_cond_timedwait"));
}
return true;
}
};
static_assert(
sizeof(condition_variable_monotonic) == sizeof(boost::condition_variable),
"sizeof(ros::internal::condition_variable_monotonic) != sizeof(boost::condition_variable)");

#endif

} // namespace internal
} // namespaec ros

#endif // ROSCPP_INTERNAL_CONDITION_VARIABLE_H
5 changes: 3 additions & 2 deletions clients/roscpp/include/ros/rosout_appender.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,9 @@
#include <ros/message_forward.h>
#include "common.h"

#include "ros/internal/condition_variable.h"

#include <boost/shared_ptr.hpp>
#include <boost/thread/condition_variable.hpp>
#include <boost/weak_ptr.hpp>

#include <boost/thread.hpp>
Expand Down Expand Up @@ -74,7 +75,7 @@ class ROSCPP_DECL ROSOutAppender : public ros::console::LogAppender
typedef std::vector<rosgraph_msgs::LogPtr> V_Log;
V_Log log_queue_;
boost::mutex queue_mutex_;
boost::condition_variable queue_condition_;
ros::internal::condition_variable_monotonic queue_condition_;
bool shutting_down_;
bool disable_topics_;

Expand Down
4 changes: 2 additions & 2 deletions clients/roscpp/include/ros/service_server_link.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,8 +36,8 @@
#define ROSCPP_SERVICE_SERVER_LINK_H

#include "ros/common.h"
#include "ros/internal/condition_variable.h"

#include <boost/thread/condition_variable.hpp>
#include <boost/thread/mutex.hpp>
#include <boost/shared_array.hpp>
#include <boost/enable_shared_from_this.hpp>
Expand Down Expand Up @@ -65,7 +65,7 @@ class ROSCPP_DECL ServiceServerLink : public boost::enable_shared_from_this<Serv
SerializedMessage* resp_;

bool finished_;
boost::condition_variable finished_condition_;
ros::internal::condition_variable_monotonic finished_condition_;
boost::mutex finished_mutex_;
boost::thread::id caller_thread_id_;

Expand Down
14 changes: 3 additions & 11 deletions clients/roscpp/include/ros/timer_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,13 +32,13 @@
#include "ros/time.h"
#include "ros/file_log.h"

#include <boost/thread/condition_variable.hpp>
#include <boost/thread/thread.hpp>
#include <boost/thread/mutex.hpp>
#include <boost/thread/recursive_mutex.hpp>

#include "ros/assert.h"
#include "ros/callback_queue_interface.h"
#include "ros/internal/condition_variable.h"

#include <vector>
#include <list>
Expand Down Expand Up @@ -130,7 +130,7 @@ class TimerManager

V_TimerInfo timers_;
boost::mutex timers_mutex_;
boost::condition_variable timers_cond_;
ros::internal::condition_variable_monotonic timers_cond_;
volatile bool new_timer_;

boost::mutex waiting_mutex_;
Expand Down Expand Up @@ -233,15 +233,7 @@ class TimerManager
template<class T, class D, class E>
TimerManager<T, D, E>::TimerManager() :
new_timer_(false), id_counter_(0), thread_started_(false), quit_(false)
{
#if !defined(BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC) && !defined(BOOST_THREAD_INTERNAL_CLOCK_IS_MONO)
ROS_ASSERT_MSG(false,
"ros::TimerManager was instantiated by package " ROS_PACKAGE_NAME ", but "
"neither BOOST_THREAD_HAS_CONDATTR_SET_CLOCK_MONOTONIC nor BOOST_THREAD_INTERNAL_CLOCK_IS_MONO is defined! "
"Be aware that timers might misbehave when system time jumps, "
"e.g. due to network time corrections.");
#endif
}
{}

template<class T, class D, class E>
TimerManager<T, D, E>::~TimerManager()
Expand Down
3 changes: 2 additions & 1 deletion clients/roscpp/include/ros/transport/transport.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@
#ifndef ROSCPP_TRANSPORT_H
#define ROSCPP_TRANSPORT_H

#include <ros/common.h>
#include <ros/types.h>
#include <boost/function.hpp>
#include <boost/shared_ptr.hpp>
Expand All @@ -52,7 +53,7 @@ class Header;
/**
* \brief Abstract base class that allows abstraction of the transport type, eg. TCP, shared memory, UDP...
*/
class Transport : public boost::enable_shared_from_this<Transport>
class ROSCPP_DECL Transport : public boost::enable_shared_from_this<Transport>
{
public:
Transport();
Expand Down

0 comments on commit f781def

Please sign in to comment.