Skip to content

Commit

Permalink
roscpp: replace ROSCPP_BOOST_CONDITION_VARIABLE and ROSCPP_BOOST_COND…
Browse files Browse the repository at this point in the history
…ITION_VARIABLE_HEADER macros by a typedef in internal_condition_variable.h
  • Loading branch information
meyerj authored and dirk-thomas committed Feb 5, 2020
1 parent dfbf726 commit b9e8f3a
Show file tree
Hide file tree
Showing 7 changed files with 66 additions and 39 deletions.
3 changes: 0 additions & 3 deletions clients/roscpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,6 @@ 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)
set(ROSCPP_USE_BACKPORTED_BOOST_CONDITION_VARIABLE_IMPLEMENTATION ON)
endif()
if(Boost_VERSION LESS 106700)
# CLOCK_MONOTONIC became the default in Boost 1.67:
# https://github.com/boostorg/thread/commit/1e84b978b2bb0aae830cc14533dea3b7ddda5cde
Expand Down
8 changes: 2 additions & 6 deletions clients/roscpp/include/ros/callback_queue.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,12 +35,8 @@
#ifndef ROSCPP_CALLBACK_QUEUE_H
#define ROSCPP_CALLBACK_QUEUE_H

// check if we might need to include our own backported version boost::condition_variable
// in order to use CLOCK_MONOTONIC for the condition variable
#include "ros/common.h"
#include ROSCPP_BOOST_CONDITION_VARIABLE_HEADER

#include "ros/callback_queue_interface.h"
#include "ros/internal_condition_variable.h"
#include "ros/time.h"

#include <boost/shared_ptr.hpp>
Expand Down Expand Up @@ -166,7 +162,7 @@ class ROSCPP_DECL CallbackQueue : public CallbackQueueInterface
D_CallbackInfo callbacks_;
size_t calling_;
boost::mutex mutex_;
ROSCPP_BOOST_CONDITION_VARIABLE condition_;
roscpp::internal::condition_variable condition_;

boost::mutex id_info_mutex_;
M_IDInfo id_info_;
Expand Down
13 changes: 0 additions & 13 deletions clients/roscpp/include/ros/common.h.in
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,6 @@
#include "ros/serialized_message.h"

#include <boost/shared_array.hpp>
#include <boost/version.hpp>

#define ROS_VERSION_MAJOR @roscpp_VERSION_MAJOR@
#define ROS_VERSION_MINOR @roscpp_VERSION_MINOR@
Expand All @@ -49,18 +48,6 @@
#define ROS_VERSION_GE(major1, minor1, patch1, major2, minor2, patch2) (ROS_VERSION_COMBINED(major1, minor1, patch1) >= ROS_VERSION_COMBINED(major2, minor2, patch2))
#define ROS_VERSION_MINIMUM(major, minor, patch) ROS_VERSION_GE(ROS_VERSION_MAJOR, ROS_VERSION_MINOR, ROS_VERSION_PATCH, major, minor, patch)

// check if we might need to include our own backported version boost::condition_variable
// in order to use CLOCK_MONOTONIC for the condition variable and for the SteadyTimer
#cmakedefine ROSCPP_USE_BACKPORTED_BOOST_CONDITION_VARIABLE_IMPLEMENTATION
#ifdef ROSCPP_USE_BACKPORTED_BOOST_CONDITION_VARIABLE_IMPLEMENTATION
// use backported version of boost condition variable, see https://svn.boost.org/trac/boost/ticket/6377
#define ROSCPP_BOOST_CONDITION_VARIABLE_HEADER "boost_161_condition_variable.h"
#define ROSCPP_BOOST_CONDITION_VARIABLE boost_161::condition_variable
#else
#define ROSCPP_BOOST_CONDITION_VARIABLE_HEADER <boost/thread/condition_variable.hpp>
#define ROSCPP_BOOST_CONDITION_VARIABLE boost::condition_variable
#endif

#include <ros/macros.h>

// Import/export for windows dll's and visibility for gcc shared libraries.
Expand Down
56 changes: 56 additions & 0 deletions clients/roscpp/include/ros/internal_condition_variable.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,56 @@
/*
* Copyright (C) 2008, Morgan Quigley and 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.
*/

#ifndef ROSCPP_INTERNAL_CONDITION_VARIABLE_H
#define ROSCPP_INTERNAL_CONDITION_VARIABLE_H

#include <boost/version.hpp>

// check if we might need to include our own backported version boost::condition_variable
// in order to use CLOCK_MONOTONIC for the condition variable and for the SteadyTimer
#if !defined(_WIN32) && !defined(__APPLE__) && (BOOST_VERSION < 106100)
#define ROSCPP_USE_BACKPORTED_BOOST_CONDITION_VARIABLE_IMPLEMENTATION
#endif

#ifdef ROSCPP_USE_BACKPORTED_BOOST_CONDITION_VARIABLE_IMPLEMENTATION
// use backported version of boost condition variable, see https://svn.boost.org/trac/boost/ticket/6377
#include "boost_161_condition_variable.h"
namespace roscpp {
namespace internal {
typedef boost_161::condition_variable condition_variable;
}
}
#else
#include <boost/thread/condition_variable.hpp>
namespace roscpp {
namespace internal {
typedef boost::condition_variable condition_variable;
}
}
#endif

#endif // ROSCPP_INTERNAL_CONDITION_VARIABLE_H
9 changes: 3 additions & 6 deletions clients/roscpp/include/ros/rosout_appender.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,11 +35,8 @@
#ifndef ROSCPP_ROSOUT_APPENDER_H
#define ROSCPP_ROSOUT_APPENDER_H

// check if we might need to include our own backported version boost::condition_variable
// in order to use CLOCK_MONOTONIC for the condition variable
#include "ros/common.h"
#include ROSCPP_BOOST_CONDITION_VARIABLE_HEADER

#include <ros/common.h>
#include <ros/internal_condition_variable.h>
#include <ros/message_forward.h>

#include <boost/shared_ptr.hpp>
Expand Down Expand Up @@ -77,7 +74,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_;
ROSCPP_BOOST_CONDITION_VARIABLE queue_condition_;
roscpp::internal::condition_variable queue_condition_;
bool shutting_down_;
bool disable_topics_;

Expand Down
8 changes: 3 additions & 5 deletions clients/roscpp/include/ros/service_server_link.h
Original file line number Diff line number Diff line change
Expand Up @@ -35,10 +35,8 @@
#ifndef ROSCPP_SERVICE_SERVER_LINK_H
#define ROSCPP_SERVICE_SERVER_LINK_H

// check if we might need to include our own backported version boost::condition_variable
// in order to use CLOCK_MONOTONIC for the condition variable
#include "ros/common.h"
#include ROSCPP_BOOST_CONDITION_VARIABLE_HEADER
#include <ros/common.h>
#include <ros/internal_condition_variable.h>

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

bool finished_;
ROSCPP_BOOST_CONDITION_VARIABLE finished_condition_;
roscpp::internal::condition_variable finished_condition_;
boost::mutex finished_mutex_;
boost::thread::id caller_thread_id_;

Expand Down
8 changes: 2 additions & 6 deletions clients/roscpp/include/ros/timer_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,8 @@
#ifndef ROSCPP_TIMER_MANAGER_H
#define ROSCPP_TIMER_MANAGER_H

// check if we might need to include our own backported version boost::condition_variable
// in order to use CLOCK_MONOTONIC for the SteadyTimer
#include "ros/common.h"
#include ROSCPP_BOOST_CONDITION_VARIABLE_HEADER

#include "ros/forwards.h"
#include "ros/internal_condition_variable.h"
#include "ros/time.h"
#include "ros/file_log.h"

Expand Down Expand Up @@ -132,7 +128,7 @@ class TimerManager

V_TimerInfo timers_;
boost::mutex timers_mutex_;
ROSCPP_BOOST_CONDITION_VARIABLE timers_cond_;
roscpp::internal::condition_variable timers_cond_;
volatile bool new_timer_;

boost::mutex waiting_mutex_;
Expand Down

0 comments on commit b9e8f3a

Please sign in to comment.