Skip to content

Commit

Permalink
Replace deprecated tbb task for tbb >= 2021 (#3174)
Browse files Browse the repository at this point in the history
As tbb::task has been removed in oneTBB 2021.01,
we need to replace its use with oneapi::tbb::task_group.
Define a wrapper so that tbb::task_group is used for
newer versions of oneTBB.

Fixes #2867.

* Fix typo
* Remove TopicManagerProcessTask as it is unused
* Use oneapi::tbb::task_group instead of tbb::task if available
* Assign my copyright to OSRF
* Add myself to AUTHORS
* Default to using tbb::task for older versions of TBB, to maintain ABI
* Replace use of tbb/version.h with tbb/tbb.h

As tbb/version.h is seemingly not present before v2021.01, it cannot be
used to get the definition for TBB_VERSION_MAJOR, so let's use the main
tbb.h header which is present on all versions.

Signed-off-by: Alex Dewar <alex.dewar@gmx.co.uk>

* Make sure that there are no ABI changes for tbb < 2021

* Fix linking problems
* Undef more emit symboles for tbb includes
* Remove trailing whitespace

Signed-off-by: Steve Peters <scpeters@openrobotics.org>

* Cleanup TAskGroup as it is used only if tbb>=2021
* If tbb >= 2021 add TBB::tbb to GAZEBO_LIBRARIES for downstream users
* Fix CMake configuration failure with tbb 2020
* Fix GAZEBO_TRANSPORT_TASKGROUP_HH_ header guard
* For tbb >= 2021 make PublishTask::operator() const
* Unpin tbb-devel

Co-authored-by: Alex Dewar <a.dewar@sussex.ac.uk>
Co-authored-by: Alex Dewar <alex.dewar@gmx.co.uk>
Co-authored-by: Steve Peters <scpeters@openrobotics.org>
  • Loading branch information
4 people authored Mar 10, 2022
1 parent 34ebf4e commit ea95601
Show file tree
Hide file tree
Showing 12 changed files with 168 additions and 11 deletions.
2 changes: 1 addition & 1 deletion .github/workflows/conda-forge.yml
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ jobs:
# Compilation related dependencies
mamba install cmake compilers make ninja pkg-config
# Actual dependencies
mamba install libprotobuf libsdformat libignition-cmake2 libignition-math6 libignition-transport8 libignition-common3 libignition-fuel-tools4 qt=5.12.9=*_4 ogre=1.10 freeimage curl tbb-devel=2020 qwt tinyxml2 libccd boost-cpp libcurl tinyxml bzip2 zlib ffmpeg graphviz libgdal libusb bullet-cpp dartsim simbody hdf5 openal-soft glib gts
mamba install libprotobuf libsdformat libignition-cmake2 libignition-math6 libignition-transport8 libignition-common3 libignition-fuel-tools4 qt=5.12.9=*_4 ogre=1.10 freeimage curl tbb-devel qwt tinyxml2 libccd boost-cpp libcurl tinyxml bzip2 zlib ffmpeg graphviz libgdal libusb bullet-cpp dartsim simbody hdf5 openal-soft glib gts
- name: Linux-only Dependencies [Linux]
if: contains(matrix.os, 'ubuntu')
Expand Down
1 change: 1 addition & 0 deletions AUTHORS
Original file line number Diff line number Diff line change
@@ -1,2 +1,3 @@
Alex Dewar <alex.dewar@gmx.co.uk>
Nate Koenig <nkoenig@osrfoundation.org>
John Hsu <hsu@osrfoundation.org>
8 changes: 7 additions & 1 deletion cmake/SearchForStuff.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -301,7 +301,7 @@ if (PKG_CONFIG_FOUND)

#################################################
# Find TBB
pkg_check_modules(TBB tbb<2021)
pkg_check_modules(TBB tbb)
set (TBB_PKG_CONFIG "tbb")
if (NOT TBB_FOUND)
message(STATUS "TBB not found, attempting to detect manually")
Expand All @@ -325,6 +325,12 @@ if (PKG_CONFIG_FOUND)
endif(tbb_library)
endif (NOT TBB_FOUND)
endif (NOT TBB_FOUND)
set(HAVE_TBB_GREATER_OR_EQUAL_2021 OFF)
if (DEFINED TBB_VERSION AND NOT ${TBB_VERSION} STREQUAL "")
if (${TBB_VERSION} VERSION_GREATER_EQUAL "2021.0")
set(HAVE_TBB_GREATER_OR_EQUAL_2021 ON)
endif()
endif()

#################################################
# Find OGRE
Expand Down
8 changes: 8 additions & 0 deletions cmake/gazebo-config.cmake.in
Original file line number Diff line number Diff line change
Expand Up @@ -222,3 +222,11 @@ list(APPEND @PKG_NAME@_LIBRARIES ${IGNITION-FUEL_TOOLS_LIBRARIES})
list(APPEND @PKG_NAME@_LDFLAGS -Wl,-rpath,${GAZEBO_INSTALL_LIB_DIR}/gazebo-@GAZEBO_MAJOR_VERSION@/plugins)
list(APPEND @PKG_NAME@_LDFLAGS -L${GAZEBO_INSTALL_LIB_DIR})
list(APPEND @PKG_NAME@_LDFLAGS -L${GAZEBO_INSTALL_LIB_DIR}/gazebo-@GAZEBO_MAJOR_VERSION@/plugins)

set (GAZEBO_HAS_TBB_GREATER_OR_EQUAL_2021 @HAVE_TBB_GREATER_OR_EQUAL_2021@)
if (GAZEBO_HAS_TBB_GREATER_OR_EQUAL_2021)
find_package(TBB CONFIG)
if (TARGET tbb::tbb)
list(APPEND @PKG_NAME@_LIBRARIES TBB::tbb)
endif ()
endif ()
7 changes: 7 additions & 0 deletions gazebo/transport/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ set (headers
SubscribeOptions.hh
Subscriber.hh
SubscriptionTransport.hh
TaskGroup.hh
TopicManager.hh
TransportIface.hh
TransportTypes.hh
Expand Down Expand Up @@ -70,6 +71,12 @@ if (WIN32)
target_link_libraries(gazebo_transport ws2_32 Iphlpapi)
endif()

if(${CMAKE_VERSION} VERSION_LESS "3.13.0")
link_directories(${TBB_LIBRARY_DIRS})
else()
target_link_directories(gazebo_transport PUBLIC ${TBB_LIBRARY_DIRS})
endif()

if (USE_PCH)
add_pch(gazebo_transport transport_pch.hh ${Boost_PKGCONFIG_CFLAGS} "-I${PROTOBUF_INCLUDE_DIR}" "-I${TBB_INCLUDEDIR}")
endif()
Expand Down
34 changes: 32 additions & 2 deletions gazebo/transport/Connection.hh
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,16 @@
#ifndef _CONNECTION_HH_
#define _CONNECTION_HH_

#undef emit
#include <tbb/task.h>
#define emit

// If TBB_VERSION_MAJOR is not defined, this means that
// tbb >= 2021 and we can include the tbb/version.h header
#ifndef TBB_VERSION_MAJOR
#include <tbb/version.h>
#endif

#include <google/protobuf/message.h>

// This fixes compiler warnings, see #3147 and #3160
Expand All @@ -41,6 +50,9 @@
#include "gazebo/common/Console.hh"
#include "gazebo/common/Exception.hh"
#include "gazebo/common/WeakBind.hh"
#if TBB_VERSION_MAJOR >= 2021
#include "gazebo/transport/TaskGroup.hh"
#endif
#include "gazebo/util/system.hh"

#define HEADER_LENGTH 8
Expand All @@ -58,7 +70,11 @@ namespace gazebo
/// \cond
/// \brief A task instance that is created when data is read from
/// a socket and used by TBB
#if TBB_VERSION_MAJOR < 2021
class GZ_TRANSPORT_VISIBLE ConnectionReadTask : public tbb::task
#else
class GZ_TRANSPORT_VISIBLE ConnectionReadTask
#endif
{
/// \brief Constructor
/// \param[_in] _func Boost function pointer, which is the function
Expand All @@ -72,14 +88,19 @@ namespace gazebo
{
}

#if TBB_VERSION_MAJOR < 2021
/// \bried Overridden function from tbb::task that exectues the data
/// callback.
public: tbb::task *execute()
{
this->func(this->data);
return NULL;
}

#else
/// \brief Execute the data callback
public: void operator()() const
{ this->func(this->data); }
#endif
/// \brief The boost function pointer
private: boost::function<void (const std::string &)> func;

Expand Down Expand Up @@ -314,12 +335,16 @@ namespace gazebo

if (!_e && !transport::is_stopped())
{
#if TBB_VERSION_MAJOR < 2021
ConnectionReadTask *task = new(tbb::task::allocate_root())
ConnectionReadTask(boost::get<0>(_handler), data);
tbb::task::enqueue(*task);

// Non-tbb version:
// boost::get<0>(_handler)(data);
#else
this->taskGroup.run<ConnectionReadTask>(boost::get<0>(_handler), data);
#endif
}
}

Expand Down Expand Up @@ -376,7 +401,7 @@ namespace gazebo
private: boost::asio::ip::tcp::endpoint GetRemoteEndpoint() const;

/// \brief Gets hostname
/// \param[in] _ep The end point to get the hostename of
/// \param[in] _ep The end point to get the hostname of
private: static std::string GetHostname(
boost::asio::ip::tcp::endpoint _ep);

Expand Down Expand Up @@ -469,6 +494,11 @@ namespace gazebo

/// \brief True if the connection is open.
private: bool isOpen;

#if TBB_VERSION_MAJOR >= 2021
/// \brief For managing asynchronous tasks with tbb
private: TaskGroup taskGroup;
#endif
};
/// \}
}
Expand Down
20 changes: 15 additions & 5 deletions gazebo/transport/ConnectionManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@
using namespace gazebo;
using namespace transport;

#if TBB_VERSION_MAJOR < 2021
/// TBB task to process nodes.
class TopicManagerProcessTask : public tbb::task
{
Expand All @@ -37,20 +38,30 @@ class TopicManagerProcessTask : public tbb::task
return NULL;
}
};
#endif

/// TBB task to establish subscriber to publisher connection.
#if TBB_VERSION_MAJOR < 2021
class TopicManagerConnectionTask : public tbb::task
#else
class TopicManagerConnectionTask
#endif
{
/// \brief Constructor.
/// \param[in] _pub Publish message
public: explicit TopicManagerConnectionTask(msgs::Publish _pub) : pub(_pub) {}

/// Implements the necessary execute function
#if TBB_VERSION_MAJOR < 2021
public: tbb::task *execute()
{
TopicManager::Instance()->ConnectSubToPub(pub);
return NULL;
}
#else
public: void operator()() const
{ TopicManager::Instance()->ConnectSubToPub(pub); }
#endif

/// \brief Publish message
private: msgs::Publish pub;
Expand Down Expand Up @@ -273,11 +284,6 @@ void ConnectionManager::RunUpdate()
if (this->masterConn)
this->masterConn->ProcessWriteQueue();

// Use TBB to process nodes. Need more testing to see if this makes
// a difference.
// TopicManagerProcessTask *task = new(tbb::task::allocate_root())
// TopicManagerProcessTask();
// tbb::task::enqueue(*task);
boost::recursive_mutex::scoped_lock lock(this->connectionMutex);

TopicManager::Instance()->ProcessNodes();
Expand Down Expand Up @@ -403,9 +409,13 @@ void ConnectionManager::ProcessMessage(const std::string &_data)
if (pub.host() != this->serverConn->GetLocalAddress() ||
pub.port() != this->serverConn->GetLocalPort())
{
#if TBB_VERSION_MAJOR < 2021
TopicManagerConnectionTask *task = new(tbb::task::allocate_root())
TopicManagerConnectionTask(pub);
tbb::task::enqueue(*task);
#else
this->taskGroup.run<TopicManagerConnectionTask>(pub);
#endif
}
}
// publisher_subscribe. This occurs when we try to subscribe to a topic, and
Expand Down
10 changes: 9 additions & 1 deletion gazebo/transport/ConnectionManager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,11 @@
#include "gazebo/msgs/msgs.hh"
#include "gazebo/common/SingletonT.hh"

#include "gazebo/transport/Publisher.hh"
#include "gazebo/transport/Connection.hh"
#include "gazebo/transport/Publisher.hh"
#if TBB_VERSION_MAJOR >= 2021
#include "gazebo/transport/TaskGroup.hh"
#endif
#include "gazebo/util/system.hh"

/// \brief Explicit instantiation for typed SingletonT.
Expand Down Expand Up @@ -194,6 +197,11 @@ namespace gazebo
/// \brief Condition used for synchronization
private: boost::condition_variable namespaceCondition;

#if TBB_VERSION_MAJOR >= 2021
/// \brief For managing asynchronous tasks with tbb
private: TaskGroup taskGroup;
#endif

// Singleton implementation
private: friend class SingletonT<ConnectionManager>;
};
Expand Down
30 changes: 29 additions & 1 deletion gazebo/transport/Node.hh
Original file line number Diff line number Diff line change
Expand Up @@ -18,19 +18,27 @@
#ifndef GAZEBO_TRANSPORT_NODE_HH_
#define GAZEBO_TRANSPORT_NODE_HH_

#undef emit
#include <tbb/task.h>
#define emit
#ifndef TBB_VERSION_MAJOR
#include <tbb/version.h>
#endif

// This fixes compiler warnings, see #3147 and #3160
#ifndef BOOST_BIND_GLOBAL_PLACEHOLDERS
#define BOOST_BIND_GLOBAL_PLACEHOLDERS
#endif

#include <boost/bind.hpp>
#include <boost/enable_shared_from_this.hpp>
#include <map>
#include <list>
#include <string>
#include <vector>

#if TBB_VERSION_MAJOR >= 2021
#include "gazebo/transport/TaskGroup.hh"
#endif
#include "gazebo/transport/TransportTypes.hh"
#include "gazebo/transport/TopicManager.hh"
#include "gazebo/util/system.hh"
Expand All @@ -41,7 +49,11 @@ namespace gazebo
{
/// \cond
/// \brief Task used by Node::Publish to publish on a one-time publisher
#if TBB_VERSION_MAJOR < 2021
class GZ_TRANSPORT_VISIBLE PublishTask : public tbb::task
#else
class GZ_TRANSPORT_VISIBLE PublishTask
#endif
{
/// \brief Constructor
/// \param[in] _pub Publisher to publish the message on.
Expand All @@ -54,16 +66,23 @@ namespace gazebo
this->msg->CopyFrom(_message);
}

#if TBB_VERSION_MAJOR < 2021
/// \brief Overridden function from tbb::task that exectues the
/// publish task.
public: tbb::task *execute()
#else
/// \brief Executes the publish task.
public: void operator()() const
#endif
{
this->pub->WaitForConnection();
this->pub->Publish(*this->msg, true);
this->pub->SendMessage();
delete this->msg;
#if TBB_VERSION_MAJOR < 2021
this->pub.reset();
return NULL;
#endif
}

/// \brief Pointer to the publisher.
Expand Down Expand Up @@ -164,11 +183,15 @@ namespace gazebo
const google::protobuf::Message &_message)
{
transport::PublisherPtr pub = this->Advertise<M>(_topic);
#if TBB_VERSION_MAJOR < 2021
PublishTask *task = new(tbb::task::allocate_root())
PublishTask(pub, _message);

tbb::task::enqueue(*task);
return;
#else
this->taskGroup.run<PublishTask>(pub, _message);
#endif
}

/// \brief Advertise a topic
Expand Down Expand Up @@ -426,6 +449,11 @@ namespace gazebo
/// \brief List of newly arrive messages
private: std::map<std::string, std::list<MessagePtr> > incomingMsgsLocal;

#if TBB_VERSION_MAJOR >= 2021
/// \brief For managing asynchronous tasks with tbb
private: TaskGroup taskGroup;
#endif

private: boost::mutex publisherMutex;
private: boost::mutex publisherDeleteMutex;
private: boost::recursive_mutex incomingMutex;
Expand Down
47 changes: 47 additions & 0 deletions gazebo/transport/TaskGroup.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,47 @@
/*
* Copyright (C) 2021 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/
#ifndef GAZEBO_TRANSPORT_TASKGROUP_HH_
#define GAZEBO_TRANSPORT_TASKGROUP_HH_

#include <utility>

// Emit is both a macro in Qt and a function defined by tbb
#undef emit
#include <tbb/tbb.h>
#define emit

namespace gazebo {
namespace transport {
class TaskGroup
{
public: ~TaskGroup() noexcept
{
// Wait for running tasks to finish
this->taskGroup.wait();
}

public: template<class Functor, class... Args> void run(Args&&... args)
{
this->taskGroup.run(Functor(std::forward<Args>(args)...));
}

private: tbb::task_group taskGroup;
};
}
}

#endif
Loading

0 comments on commit ea95601

Please sign in to comment.