Skip to content

Commit

Permalink
Add foxglove_bridge package (#345)
Browse files Browse the repository at this point in the history
* Add ros-foxglove-bridge package

* Fix name

* Add patch for actionlib to use missing boost::placeholders namespace

The patch comes from ros/actionlib@d675dd7.
You can retrieve the patch by adding `.patch` to the url.

* remove windows build

* Add patch for ros-babel-fish

* kick ci

* Only rebuild selected packages (including actionlib)

* Remove old channel

* Add babel-fish-test-msgs

* babel-fish-test-msgs -> ros-babel-fish-test-msgs

* Add websocketpp mapping

* Add websocketpp mapping

* testpr workflow: Set ROS_VERSION to 1

* fix malformed ros-babel-fish patch

* Update ros-babel-fish patch

* Update ros-babel-fish patch

* Update actionlib patch (whitespace changes)

* Update ros-babel-fish patch

* Update ros-babel-fish patch

* Update ros-babel-fish patch

* Update ros-babel-fish patch

* Add patch for foxglove-bridge

* Update foxglove-bridge patch

* Update foxglove-bridge patch

* Update ros-babel-fish patch

* Update foxglove-bridge patch

* Update ros-babel-fish patch

* update patches

* Update ros-babel-fish patch

* Update foxglove-bridge patch

* Update foxglove-bridge patch

* Update foxglove-bridge patch

* Update foxglove-bridge patch

* Update ros-noetic-foxglove-bridge.patch

---------

Co-authored-by: Hans-Joachim Krauch <[email protected]>
Co-authored-by: Tobias Fischer <[email protected]>
Co-authored-by: Hans-Joachim Krauch <[email protected]>
  • Loading branch information
4 people authored Mar 11, 2023
1 parent c81602b commit 1f7fd77
Show file tree
Hide file tree
Showing 12 changed files with 1,380 additions and 493 deletions.
1 change: 0 additions & 1 deletion .github/testpr_environment.yml
Original file line number Diff line number Diff line change
@@ -1,6 +1,5 @@
name: testpr_env
channels:
- robostack
- robostack-staging
- conda-forge
dependencies:
Expand Down
3 changes: 3 additions & 0 deletions .github/workflows/testpr.yml
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@ on:
pull_request:
paths:
- '*.yaml'

env:
ROS_VERSION: 1

jobs:
build:
Expand Down
2 changes: 2 additions & 0 deletions conda.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -898,6 +898,8 @@ uuid:
win64: []
virtualenv:
conda: [virtualenv]
libwebsocketpp-dev:
conda: [websocketpp]
wget:
conda: [wget]
wx-common:
Expand Down
264 changes: 264 additions & 0 deletions patch/ros-noetic-actionlib.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,264 @@
diff --git a/actionlib/include/actionlib/client/action_client.h b/actionlib/include/actionlib/client/action_client.h
index 85b32dc..21d0102 100644
--- a/actionlib/include/actionlib/client/action_client.h
+++ b/actionlib/include/actionlib/client/action_client.h
@@ -236,17 +236,17 @@ private:

// Start publishers and subscribers
goal_pub_ = queue_advertise<ActionGoal>("goal", static_cast<uint32_t>(pub_queue_size),
- boost::bind(&ConnectionMonitor::goalConnectCallback, connection_monitor_, _1),
- boost::bind(&ConnectionMonitor::goalDisconnectCallback, connection_monitor_, _1),
+ boost::bind(&ConnectionMonitor::goalConnectCallback, connection_monitor_, boost::placeholders::_1),
+ boost::bind(&ConnectionMonitor::goalDisconnectCallback, connection_monitor_, boost::placeholders::_1),
queue);
cancel_pub_ =
queue_advertise<actionlib_msgs::GoalID>("cancel", static_cast<uint32_t>(pub_queue_size),
- boost::bind(&ConnectionMonitor::cancelConnectCallback, connection_monitor_, _1),
- boost::bind(&ConnectionMonitor::cancelDisconnectCallback, connection_monitor_, _1),
+ boost::bind(&ConnectionMonitor::cancelConnectCallback, connection_monitor_, boost::placeholders::_1),
+ boost::bind(&ConnectionMonitor::cancelDisconnectCallback, connection_monitor_, boost::placeholders::_1),
queue);

- manager_.registerSendGoalFunc(boost::bind(&ActionClientT::sendGoalFunc, this, _1));
- manager_.registerCancelFunc(boost::bind(&ActionClientT::sendCancelFunc, this, _1));
+ manager_.registerSendGoalFunc(boost::bind(&ActionClientT::sendGoalFunc, this, boost::placeholders::_1));
+ manager_.registerCancelFunc(boost::bind(&ActionClientT::sendCancelFunc, this, boost::placeholders::_1));
}

template<class M>
@@ -275,7 +275,7 @@ private:
ops.datatype = ros::message_traits::datatype<M>();
ops.helper = ros::SubscriptionCallbackHelperPtr(
new ros::SubscriptionCallbackHelperT<const ros::MessageEvent<M const> &>(
- boost::bind(fp, obj, _1)
+ boost::bind(fp, obj, boost::placeholders::_1)
)
);
return n_.subscribe(ops);
diff --git a/actionlib/include/actionlib/client/goal_manager_imp.h b/actionlib/include/actionlib/client/goal_manager_imp.h
index 28f4979..4e3281b 100644
--- a/actionlib/include/actionlib/client/goal_manager_imp.h
+++ b/actionlib/include/actionlib/client/goal_manager_imp.h
@@ -74,7 +74,7 @@ ClientGoalHandle<ActionSpec> GoalManager<ActionSpec>::initGoal(const Goal & goal

boost::recursive_mutex::scoped_lock lock(list_mutex_);
typename ManagedListT::Handle list_handle =
- list_.add(comm_state_machine, boost::bind(&GoalManagerT::listElemDeleter, this, _1), guard_);
+ list_.add(comm_state_machine, boost::bind(&GoalManagerT::listElemDeleter, this, boost::placeholders::_1), guard_);

if (send_goal_func_) {
send_goal_func_(action_goal);
diff --git a/actionlib/include/actionlib/client/simple_action_client.h b/actionlib/include/actionlib/client/simple_action_client.h
index 436516f..02df1ae 100644
--- a/actionlib/include/actionlib/client/simple_action_client.h
+++ b/actionlib/include/actionlib/client/simple_action_client.h
@@ -330,8 +330,8 @@ void SimpleActionClient<ActionSpec>::sendGoal(const Goal & goal,
cur_simple_state_ = SimpleGoalState::PENDING;

// Send the goal to the ActionServer
- gh_ = ac_->sendGoal(goal, boost::bind(&SimpleActionClientT::handleTransition, this, _1),
- boost::bind(&SimpleActionClientT::handleFeedback, this, _1, _2));
+ gh_ = ac_->sendGoal(goal, boost::bind(&SimpleActionClientT::handleTransition, this, boost::placeholders::_1),
+ boost::bind(&SimpleActionClientT::handleFeedback, this, boost::placeholders::_1, boost::placeholders::_2));
}

template<class ActionSpec>
diff --git a/actionlib/include/actionlib/managed_list.h b/actionlib/include/actionlib/managed_list.h
index 2c91960..b2c4f89 100644
--- a/actionlib/include/actionlib/managed_list.h
+++ b/actionlib/include/actionlib/managed_list.h
@@ -218,7 +218,7 @@ private:
*/
Handle add(const T & elem)
{
- return add(elem, boost::bind(&ManagedList<T>::defaultDeleter, this, _1) );
+ return add(elem, boost::bind(&ManagedList<T>::defaultDeleter, this, boost::placeholders::_1) );
}

/**
diff --git a/actionlib/include/actionlib/one_shot_timer.h b/actionlib/include/actionlib/one_shot_timer.h
index e3c821d..7839294 100644
--- a/actionlib/include/actionlib/one_shot_timer.h
+++ b/actionlib/include/actionlib/one_shot_timer.h
@@ -60,7 +60,7 @@ public:

boost::function<void(const ros::TimerEvent & e)> getCb()
{
- return boost::bind(&OneShotTimer::cb, this, _1);
+ return boost::bind(&OneShotTimer::cb, this, boost::placeholders::_1);
}

void registerOneShotCb(boost::function<void(const ros::TimerEvent & e)> callback)
diff --git a/actionlib/include/actionlib/server/action_server_imp.h b/actionlib/include/actionlib/server/action_server_imp.h
index 2a088b1..837b9c4 100644
--- a/actionlib/include/actionlib/server/action_server_imp.h
+++ b/actionlib/include/actionlib/server/action_server_imp.h
@@ -172,15 +172,15 @@ void ActionServer<ActionSpec>::initialize()

if (status_frequency > 0) {
status_timer_ = node_.createTimer(ros::Duration(1.0 / status_frequency),
- boost::bind(&ActionServer::publishStatus, this, _1));
+ boost::bind(&ActionServer::publishStatus, this, boost::placeholders::_1));
}

goal_sub_ = node_.subscribe<ActionGoal>("goal", static_cast<uint32_t>(sub_queue_size),
- boost::bind(&ActionServerBase<ActionSpec>::goalCallback, this, _1));
+ boost::bind(&ActionServerBase<ActionSpec>::goalCallback, this, boost::placeholders::_1));

cancel_sub_ =
node_.subscribe<actionlib_msgs::GoalID>("cancel", static_cast<uint32_t>(sub_queue_size),
- boost::bind(&ActionServerBase<ActionSpec>::cancelCallback, this, _1));
+ boost::bind(&ActionServerBase<ActionSpec>::cancelCallback, this, boost::placeholders::_1));
}

template<class ActionSpec>
diff --git a/actionlib/include/actionlib/server/service_server_imp.h b/actionlib/include/actionlib/server/service_server_imp.h
index ac5444d..2f0265e 100644
--- a/actionlib/include/actionlib/server/service_server_imp.h
+++ b/actionlib/include/actionlib/server/service_server_imp.h
@@ -58,7 +58,7 @@ ServiceServerImpT<ActionSpec>::ServiceServerImpT(ros::NodeHandle n, std::string
: service_cb_(service_cb)
{
as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n, name,
- boost::bind(&ServiceServerImpT::goalCB, this, _1), false));
+ boost::bind(&ServiceServerImpT::goalCB, this, boost::placeholders::_1), false));
as_->start();
}

diff --git a/actionlib/include/actionlib/server/simple_action_server_imp.h b/actionlib/include/actionlib/server/simple_action_server_imp.h
index 0255515..a361cd7 100644
--- a/actionlib/include/actionlib/server/simple_action_server_imp.h
+++ b/actionlib/include/actionlib/server/simple_action_server_imp.h
@@ -56,8 +56,8 @@ SimpleActionServer<ActionSpec>::SimpleActionServer(std::string name,

// create the action server
as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n_, name,
- boost::bind(&SimpleActionServer::goalCallback, this, _1),
- boost::bind(&SimpleActionServer::preemptCallback, this, _1),
+ boost::bind(&SimpleActionServer::goalCallback, this, boost::placeholders::_1),
+ boost::bind(&SimpleActionServer::preemptCallback, this, boost::placeholders::_1),
auto_start));
}

@@ -68,8 +68,8 @@ SimpleActionServer<ActionSpec>::SimpleActionServer(std::string name, bool auto_s
{
// create the action server
as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n_, name,
- boost::bind(&SimpleActionServer::goalCallback, this, _1),
- boost::bind(&SimpleActionServer::preemptCallback, this, _1),
+ boost::bind(&SimpleActionServer::goalCallback, this, boost::placeholders::_1),
+ boost::bind(&SimpleActionServer::preemptCallback, this, boost::placeholders::_1),
auto_start));

if (execute_callback_) {
@@ -85,8 +85,8 @@ SimpleActionServer<ActionSpec>::SimpleActionServer(std::string name,
{
// create the action server
as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n_, name,
- boost::bind(&SimpleActionServer::goalCallback, this, _1),
- boost::bind(&SimpleActionServer::preemptCallback, this, _1),
+ boost::bind(&SimpleActionServer::goalCallback, this, boost::placeholders::_1),
+ boost::bind(&SimpleActionServer::preemptCallback, this, boost::placeholders::_1),
true));

if (execute_callback_) {
@@ -104,8 +104,8 @@ SimpleActionServer<ActionSpec>::SimpleActionServer(ros::NodeHandle n, std::strin
{
// create the action server
as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n, name,
- boost::bind(&SimpleActionServer::goalCallback, this, _1),
- boost::bind(&SimpleActionServer::preemptCallback, this, _1),
+ boost::bind(&SimpleActionServer::goalCallback, this, boost::placeholders::_1),
+ boost::bind(&SimpleActionServer::preemptCallback, this, boost::placeholders::_1),
auto_start));

if (execute_callback_) {
@@ -121,8 +121,8 @@ SimpleActionServer<ActionSpec>::SimpleActionServer(ros::NodeHandle n, std::strin
{
// create the action server
as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n, name,
- boost::bind(&SimpleActionServer::goalCallback, this, _1),
- boost::bind(&SimpleActionServer::preemptCallback, this, _1),
+ boost::bind(&SimpleActionServer::goalCallback, this, boost::placeholders::_1),
+ boost::bind(&SimpleActionServer::preemptCallback, this, boost::placeholders::_1),
auto_start));

if (execute_callback_) {
@@ -138,8 +138,8 @@ SimpleActionServer<ActionSpec>::SimpleActionServer(ros::NodeHandle n, std::strin
{
// create the action server
as_ = boost::shared_ptr<ActionServer<ActionSpec> >(new ActionServer<ActionSpec>(n, name,
- boost::bind(&SimpleActionServer::goalCallback, this, _1),
- boost::bind(&SimpleActionServer::preemptCallback, this, _1),
+ boost::bind(&SimpleActionServer::goalCallback, this, boost::placeholders::_1),
+ boost::bind(&SimpleActionServer::preemptCallback, this, boost::placeholders::_1),
true));

if (execute_callback_) {
diff --git a/actionlib/test/add_two_ints_server.cpp b/actionlib/test/add_two_ints_server.cpp
index 098c315..84ddace 100644
--- a/actionlib/test/add_two_ints_server.cpp
+++ b/actionlib/test/add_two_ints_server.cpp
@@ -53,7 +53,7 @@ int main(int argc, char ** argv)

actionlib::ServiceServer service = actionlib::advertiseService<actionlib::TwoIntsAction>(n,
"add_two_ints",
- boost::bind(add, _1, _2));
+ boost::bind(add, boost::placeholders::_1, boost::placeholders::_2));

ros::spin();

diff --git a/actionlib/test/ref_server.cpp b/actionlib/test/ref_server.cpp
index 1da0ab5..7aede23 100644
--- a/actionlib/test/ref_server.cpp
+++ b/actionlib/test/ref_server.cpp
@@ -61,8 +61,8 @@ using namespace actionlib;

RefServer::RefServer(ros::NodeHandle & n, const std::string & name)
: ActionServer<TestAction>(n, name,
- boost::bind(&RefServer::goalCallback, this, _1),
- boost::bind(&RefServer::cancelCallback, this, _1),
+ boost::bind(&RefServer::goalCallback, this, boost::placeholders::_1),
+ boost::bind(&RefServer::cancelCallback, this, boost::placeholders::_1),
false)
{
start();
diff --git a/actionlib/test/server_goal_handle_destruction.cpp b/actionlib/test/server_goal_handle_destruction.cpp
index 9e179c7..ed12d2b 100644
--- a/actionlib/test/server_goal_handle_destruction.cpp
+++ b/actionlib/test/server_goal_handle_destruction.cpp
@@ -67,7 +67,7 @@ ServerGoalHandleDestructionTester::ServerGoalHandleDestructionTester()
as_ = new ActionServer<TestAction>(nh_, "reference_action", false);
as_->start();
as_->registerGoalCallback(boost::bind(&ServerGoalHandleDestructionTester::goalCallback, this,
- _1));
+ boost::placeholders::_1));
gh_ = new GoalHandle();
}

diff --git a/actionlib/test/simple_client_test.cpp b/actionlib/test/simple_client_test.cpp
index 341bbc9..ea40050 100644
--- a/actionlib/test/simple_client_test.cpp
+++ b/actionlib/test/simple_client_test.cpp
@@ -106,7 +106,7 @@ TEST(SimpleClient, easy_callback)

bool called = false;
goal.goal = 1;
- SimpleActionClient<TestAction>::SimpleDoneCallback func = boost::bind(&easyDoneCallback, &called, &client, _1, _2);
+ SimpleActionClient<TestAction>::SimpleDoneCallback func = boost::bind(&easyDoneCallback, &called, &client, boost::placeholders::_1, boost::placeholders::_2);
client.sendGoal(goal, func);
finished = client.waitForResult(ros::Duration(10.0));
ASSERT_TRUE(finished);
diff --git a/actionlib/test/simple_execute_ref_server.cpp b/actionlib/test/simple_execute_ref_server.cpp
index 57aa9cd..b663ec4 100644
--- a/actionlib/test/simple_execute_ref_server.cpp
+++ b/actionlib/test/simple_execute_ref_server.cpp
@@ -61,7 +61,7 @@ using namespace actionlib;

SimpleExecuteRefServer::SimpleExecuteRefServer()
: as_(nh_, "reference_action", boost::bind(&SimpleExecuteRefServer::executeCallback, this,
- _1), false)
+ boost::placeholders::_1), false)
{
as_.start();
}
53 changes: 53 additions & 0 deletions patch/ros-noetic-foxglove-bridge.patch
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
diff --git a/CMakeLists.txt b/CMakeLists.txt
index efc65dc..994d91b 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -14,6 +14,11 @@ project(foxglove_bridge LANGUAGES CXX VERSION 0.5.1)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_STANDARD_REQUIRED ON)

+if(MSVC)
+ set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS TRUE)
+ set(BUILD_SHARED_LIBS TRUE)
+endif()
+
macro(enable_strict_compiler_warnings target)
target_compile_options(${target} PRIVATE
$<$<CXX_COMPILER_ID:MSVC>:/WX /W4>
@@ -47,7 +52,7 @@ add_library(foxglove_bridge_base SHARED
foxglove_bridge_base/src/test/test_client.cpp
)
target_include_directories(foxglove_bridge_base
- PUBLIC
+ SYSTEM PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/foxglove_bridge_base/include>
$<INSTALL_INTERFACE:include>
)
@@ -62,7 +67,11 @@ if(nlohmann_json_FOUND)
else()
message(STATUS "nlohmann_json not found, will search at compile time")
endif()
-enable_strict_compiler_warnings(foxglove_bridge_base)
+# enable_strict_compiler_warnings(foxglove_bridge_base)
+target_compile_definitions(foxglove_bridge_base PUBLIC _WEBSOCKETPP_CPP11_STL_)
+
+set(ENV{ROS_VERSION} 1)
+set(ENV{ROS_DISTRO} noetic)

message(STATUS "ROS_VERSION: " $ENV{ROS_VERSION})
message(STATUS "ROS_DISTRO: " $ENV{ROS_DISTRO})
diff --git a/ros1_foxglove_bridge/src/ros1_foxglove_bridge_nodelet.cpp b/ros1_foxglove_bridge/src/ros1_foxglove_bridge_nodelet.cpp
index 83a8ab5..4022a8f 100644
--- a/ros1_foxglove_bridge/src/ros1_foxglove_bridge_nodelet.cpp
+++ b/ros1_foxglove_bridge/src/ros1_foxglove_bridge_nodelet.cpp
@@ -453,8 +453,8 @@ private:
try {
channelPublicationIt->second.publish(msg);
} catch (const std::exception& ex) {
- ROS_ERROR("Failed to publish message on topic '%s'",
- channelPublicationIt->second.getTopic().c_str());
+ ROS_ERROR("Failed to publish message on topic '%s': %s",
+ channelPublicationIt->second.getTopic().c_str(), ex.what());
}
}

Loading

0 comments on commit 1f7fd77

Please sign in to comment.