From 7a80a0ee87a8e061a961d416b886363071763047 Mon Sep 17 00:00:00 2001 From: Patrick Roncagliolo Date: Tue, 9 Apr 2024 09:58:50 +0200 Subject: [PATCH 1/4] Make Player a `rosbag2` component Signed-off-by: Patrick Roncagliolo --- rosbag2/CMakeLists.txt | 58 ++++++++++++++++++++++++ rosbag2/src/rosbag2/component_player.cpp | 14 ++++++ 2 files changed, 72 insertions(+) create mode 100644 rosbag2/src/rosbag2/component_player.cpp diff --git a/rosbag2/CMakeLists.txt b/rosbag2/CMakeLists.txt index 407d502b35..e2e493286c 100644 --- a/rosbag2/CMakeLists.txt +++ b/rosbag2/CMakeLists.txt @@ -1,5 +1,63 @@ cmake_minimum_required(VERSION 3.5) project(rosbag2) +# Default to C99 +if(NOT CMAKE_C_STANDARD) + set(CMAKE_C_STANDARD 99) +endif() + +# Default to C++17 +if(NOT CMAKE_CXX_STANDARD) + set(CMAKE_CXX_STANDARD 17) + set(CMAKE_CXX_STANDARD_REQUIRED ON) +endif() + +if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") + add_compile_options(-Wall -Wextra -Wpedantic) +endif() +if(CMAKE_BUILD_TYPE STREQUAL "Debug" AND MSVC) + # /bigobj is needed to avoid error C1128: + # https://msdn.microsoft.com/en-us/library/8578y171.aspx + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /bigobj") +endif() + +# Windows supplies macros for min and max by default. We should only use min and max from stl +if(WIN32) + add_definitions(-DNOMINMAX) +endif() + find_package(ament_cmake REQUIRED) +find_package(rclcpp_components REQUIRED) +find_package(rosbag2_transport REQUIRED) + +add_library(${PROJECT_NAME} SHARED + src/rosbag2/component_player.cpp +) + +target_link_libraries(${PROJECT_NAME} + rclcpp::rclcpp + ${rclcpp_components_TARGETS} + rosbag2_transport::rosbag2_transport +) + +rclcpp_components_register_node(${PROJECT_NAME} + PLUGIN "rosbag2::Player" + EXECUTABLE player +) + +install( + TARGETS ${PROJECT_NAME} + EXPORT export_${PROJECT_NAME} + ARCHIVE DESTINATION lib + LIBRARY DESTINATION lib + RUNTIME DESTINATION bin +) + +ament_export_libraries(${PROJECT_NAME}) + +ament_export_dependencies( + rclcpp_components + rosbag2_transport +) + ament_package() diff --git a/rosbag2/src/rosbag2/component_player.cpp b/rosbag2/src/rosbag2/component_player.cpp new file mode 100644 index 0000000000..82235b0158 --- /dev/null +++ b/rosbag2/src/rosbag2/component_player.cpp @@ -0,0 +1,14 @@ +#include "rosbag2_transport/player.hpp" + +namespace rosbag2 { +class Player : public rosbag2_transport::Player { + using rosbag2_transport::Player::Player; +}; +} + +#include "rclcpp_components/register_node_macro.hpp" + +// Register the component with class_loader. +// This acts as a sort of entry point, allowing the component to be +// discoverable when its library is being loaded into a running process. +RCLCPP_COMPONENTS_REGISTER_NODE(rosbag2::Player) \ No newline at end of file From c00bf42186e5576a73a9a12befba125389adce7f Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Tue, 10 Dec 2024 00:05:18 -0800 Subject: [PATCH 2/4] Review fixes in rosbag2 composable player - Cleanups in CMakeLists.txt - Expose only the necessary constructors in rosbag2::player - Add visibility control - Add missing dependencies in package.xml - Add component_player.hpp file Signed-off-by: Michael Orlov --- rosbag2/CMakeLists.txt | 47 ++++++---------- rosbag2/include/rosbag2/component_player.hpp | 56 +++++++++++++++++++ .../include/rosbag2/visibility_control.hpp | 56 +++++++++++++++++++ rosbag2/package.xml | 5 +- rosbag2/src/rosbag2/component_player.cpp | 41 +++++++++++--- rosbag2_transport/CMakeLists.txt | 2 + 6 files changed, 167 insertions(+), 40 deletions(-) create mode 100644 rosbag2/include/rosbag2/component_player.hpp create mode 100644 rosbag2/include/rosbag2/visibility_control.hpp diff --git a/rosbag2/CMakeLists.txt b/rosbag2/CMakeLists.txt index e2e493286c..41624ec940 100644 --- a/rosbag2/CMakeLists.txt +++ b/rosbag2/CMakeLists.txt @@ -12,52 +12,37 @@ if(NOT CMAKE_CXX_STANDARD) set(CMAKE_CXX_STANDARD_REQUIRED ON) endif() -if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang") - add_compile_options(-Wall -Wextra -Wpedantic) -endif() -if(CMAKE_BUILD_TYPE STREQUAL "Debug" AND MSVC) - # /bigobj is needed to avoid error C1128: - # https://msdn.microsoft.com/en-us/library/8578y171.aspx - set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} /bigobj") -endif() - -# Windows supplies macros for min and max by default. We should only use min and max from stl -if(WIN32) - add_definitions(-DNOMINMAX) -endif() - find_package(ament_cmake REQUIRED) +find_package(rclcpp REQUIRED) find_package(rclcpp_components REQUIRED) find_package(rosbag2_transport REQUIRED) -add_library(${PROJECT_NAME} SHARED +# Library for Rosbag2 composable nodes +add_library(${PROJECT_NAME}_nodes SHARED src/rosbag2/component_player.cpp +# src/rosbag2/composable_recorder.cpp ) +target_include_directories(${PROJECT_NAME}_nodes PUBLIC + $ + $) -target_link_libraries(${PROJECT_NAME} - rclcpp::rclcpp - ${rclcpp_components_TARGETS} - rosbag2_transport::rosbag2_transport -) +ament_target_dependencies(${PROJECT_NAME}_nodes rclcpp rclcpp_components rosbag2_transport) + +rclcpp_components_register_node(${PROJECT_NAME}_nodes PLUGIN "rosbag2::Player" EXECUTABLE player) -rclcpp_components_register_node(${PROJECT_NAME} - PLUGIN "rosbag2::Player" - EXECUTABLE player +install(DIRECTORY include/ + DESTINATION include/${PROJECT_NAME} ) install( - TARGETS ${PROJECT_NAME} - EXPORT export_${PROJECT_NAME} + TARGETS ${PROJECT_NAME}_nodes + EXPORT export_${PROJECT_NAME}_nodes ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION bin ) -ament_export_libraries(${PROJECT_NAME}) - -ament_export_dependencies( - rclcpp_components - rosbag2_transport -) +# Export modern CMake targets +ament_export_targets(export_${PROJECT_NAME}_nodes) ament_package() diff --git a/rosbag2/include/rosbag2/component_player.hpp b/rosbag2/include/rosbag2/component_player.hpp new file mode 100644 index 0000000000..878954cb59 --- /dev/null +++ b/rosbag2/include/rosbag2/component_player.hpp @@ -0,0 +1,56 @@ +// Copyright 2024 Open Source Robotics Foundation, Inc. +// +// 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. + +/* This header must be included by all rclcpp headers which declare symbols + * which are defined in the rclcpp library. When not building the rclcpp + * library, i.e. when using the headers in other package's code, the contents + * of this header change the visibility of certain symbols which the rclcpp + * library cannot have, but the consuming code must have inorder to link. + */ + +#ifndef ROSBAG2__COMPONENT_PLAYER_HPP_ +#define ROSBAG2__COMPONENT_PLAYER_HPP_ + +#include + +#include "rclcpp/node_options.hpp" +#include "rosbag2/visibility_control.hpp" +#include "rosbag2_transport/player.hpp" + +namespace rosbag2 +{ +class Player : public rosbag2_transport::Player { +public: + /// \brief Constructor and entry point for the composable player. + /// Will call Player(node_name, node_options) constructor with node_name = "rosbag2_player". + /// \param node_options Node options which will be used during construction of the underlying + /// node. + ROSBAG2_PUBLIC + explicit Player(const rclcpp::NodeOptions & node_options); + + /// \brief Default constructor and entry point for the composable player. + /// Will construct Player class and initialize play_options, storage_options from node + /// parameters. At the end will call Player::play() to automatically start playback in a + /// separate thread. + /// \param node_name Name for the underlying node. + /// \param node_options Node options which will be used during construction of the underlying + /// node. + ROSBAG2_PUBLIC + explicit Player( + const std::string & node_name = "rosbag2_player", + const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions()); +}; +} // namespace rosbag2 + +#endif // ROSBAG2__COMPONENT_PLAYER_HPP_ diff --git a/rosbag2/include/rosbag2/visibility_control.hpp b/rosbag2/include/rosbag2/visibility_control.hpp new file mode 100644 index 0000000000..6070ae721f --- /dev/null +++ b/rosbag2/include/rosbag2/visibility_control.hpp @@ -0,0 +1,56 @@ +// Copyright 2024 Open Source Robotics Foundation, Inc. +// +// 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. + +/* This header must be included by all rclcpp headers which declare symbols + * which are defined in the rclcpp library. When not building the rclcpp + * library, i.e. when using the headers in other package's code, the contents + * of this header change the visibility of certain symbols which the rclcpp + * library cannot have, but the consuming code must have inorder to link. + */ + +#ifndef ROSBAG2__VISIBILITY_CONTROL_HPP_ +#define ROSBAG2__VISIBILITY_CONTROL_HPP_ + +// This logic was borrowed (then namespaced) from the examples on the gcc wiki: +// https://gcc.gnu.org/wiki/Visibility + +#if defined _WIN32 || defined __CYGWIN__ +#ifdef __GNUC__ + #define ROSBAG2_EXPORT __attribute__ ((dllexport)) + #define ROSBAG2_IMPORT __attribute__ ((dllimport)) + #else + #define ROSBAG2_EXPORT __declspec(dllexport) + #define ROSBAG2_IMPORT __declspec(dllimport) + #endif + #ifdef ROSBAG2_BUILDING_LIBRARY + #define ROSBAG2_PUBLIC ROSBAG2_EXPORT + #else + #define ROSBAG2_PUBLIC ROSBAG2_IMPORT + #endif + #define ROSBAG2_PUBLIC_TYPE ROSBAG2_PUBLIC + #define ROSBAG2_LOCAL +#else +#define ROSBAG2_EXPORT __attribute__ ((visibility("default"))) +#define ROSBAG2_IMPORT +#if __GNUC__ >= 4 +#define ROSBAG2_PUBLIC __attribute__ ((visibility("default"))) +#define ROSBAG2_LOCAL __attribute__ ((visibility("hidden"))) +#else +#define ROSBAG2_PUBLIC + #define ROSBAG2_LOCAL +#endif +#define ROSBAG2_PUBLIC_TYPE +#endif + +#endif // ROSBAG2__VISIBILITY_CONTROL_HPP_ diff --git a/rosbag2/package.xml b/rosbag2/package.xml index 70c4d62527..34202a1aae 100644 --- a/rosbag2/package.xml +++ b/rosbag2/package.xml @@ -12,12 +12,15 @@ ament_cmake + rclcpp + rclcpp_components + rosbag2_transport + ros2bag rosbag2_compression rosbag2_cpp rosbag2_py rosbag2_storage - rosbag2_transport rosbag2_compression_zstd diff --git a/rosbag2/src/rosbag2/component_player.cpp b/rosbag2/src/rosbag2/component_player.cpp index 82235b0158..5af1114126 100644 --- a/rosbag2/src/rosbag2/component_player.cpp +++ b/rosbag2/src/rosbag2/component_player.cpp @@ -1,14 +1,39 @@ -#include "rosbag2_transport/player.hpp" +// Copyright 2024 Open Source Robotics Foundation, Inc. +// +// 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. -namespace rosbag2 { -class Player : public rosbag2_transport::Player { - using rosbag2_transport::Player::Player; -}; -} +/* This header must be included by all rclcpp headers which declare symbols + * which are defined in the rclcpp library. When not building the rclcpp + * library, i.e. when using the headers in other package's code, the contents + * of this header change the visibility of certain symbols which the rclcpp + * library cannot have, but the consuming code must have inorder to link. + */ #include "rclcpp_components/register_node_macro.hpp" +#include "rosbag2/component_player.hpp" + +namespace rosbag2 +{ +Player::Player(const rclcpp::NodeOptions & node_options) +: Player("rosbag2_player", node_options) {} + +Player::Player( + const std::string & node_name, + const rclcpp::NodeOptions & node_options) +: rosbag2_transport::Player(node_name, node_options) {} +} // namespace rosbag2 // Register the component with class_loader. -// This acts as a sort of entry point, allowing the component to be +// This acts as an entry point, allowing the component to be // discoverable when its library is being loaded into a running process. -RCLCPP_COMPONENTS_REGISTER_NODE(rosbag2::Player) \ No newline at end of file +RCLCPP_COMPONENTS_REGISTER_NODE(rosbag2::Player) diff --git a/rosbag2_transport/CMakeLists.txt b/rosbag2_transport/CMakeLists.txt index 3183672554..e3670d7c6a 100644 --- a/rosbag2_transport/CMakeLists.txt +++ b/rosbag2_transport/CMakeLists.txt @@ -72,9 +72,11 @@ target_link_libraries(${PROJECT_NAME} PRIVATE yaml-cpp::yaml-cpp ) +# rosbag2_transport::Player composable node is deprecated. Please use rosbag2::Player instead rclcpp_components_register_node( ${PROJECT_NAME} PLUGIN "rosbag2_transport::Player" EXECUTABLE player) +# rosbag2_transport::Recorder composable node is deprecated. Please use rosbag2::Recorder instead rclcpp_components_register_node( ${PROJECT_NAME} PLUGIN "rosbag2_transport::Recorder" EXECUTABLE recorder) From 4f6414e625ceac7a57275730196f62c357531a0b Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Tue, 10 Dec 2024 00:12:50 -0800 Subject: [PATCH 3/4] Rename component_player.{cpp}hpp to the composable_player.{cpp}hpp Signed-off-by: Michael Orlov --- rosbag2/CMakeLists.txt | 2 +- .../rosbag2/{component_player.hpp => composable_player.hpp} | 6 +++--- .../rosbag2/{component_player.cpp => composable_player.cpp} | 2 +- 3 files changed, 5 insertions(+), 5 deletions(-) rename rosbag2/include/rosbag2/{component_player.hpp => composable_player.hpp} (94%) rename rosbag2/src/rosbag2/{component_player.cpp => composable_player.cpp} (97%) diff --git a/rosbag2/CMakeLists.txt b/rosbag2/CMakeLists.txt index 41624ec940..1ea62540cb 100644 --- a/rosbag2/CMakeLists.txt +++ b/rosbag2/CMakeLists.txt @@ -19,7 +19,7 @@ find_package(rosbag2_transport REQUIRED) # Library for Rosbag2 composable nodes add_library(${PROJECT_NAME}_nodes SHARED - src/rosbag2/component_player.cpp + src/rosbag2/composable_player.cpp # src/rosbag2/composable_recorder.cpp ) target_include_directories(${PROJECT_NAME}_nodes PUBLIC diff --git a/rosbag2/include/rosbag2/component_player.hpp b/rosbag2/include/rosbag2/composable_player.hpp similarity index 94% rename from rosbag2/include/rosbag2/component_player.hpp rename to rosbag2/include/rosbag2/composable_player.hpp index 878954cb59..7a82097b5d 100644 --- a/rosbag2/include/rosbag2/component_player.hpp +++ b/rosbag2/include/rosbag2/composable_player.hpp @@ -19,8 +19,8 @@ * library cannot have, but the consuming code must have inorder to link. */ -#ifndef ROSBAG2__COMPONENT_PLAYER_HPP_ -#define ROSBAG2__COMPONENT_PLAYER_HPP_ +#ifndef ROSBAG2__COMPOSABLE_PLAYER_HPP_ +#define ROSBAG2__COMPOSABLE_PLAYER_HPP_ #include @@ -53,4 +53,4 @@ class Player : public rosbag2_transport::Player { }; } // namespace rosbag2 -#endif // ROSBAG2__COMPONENT_PLAYER_HPP_ +#endif // ROSBAG2__COMPOSABLE_PLAYER_HPP_ diff --git a/rosbag2/src/rosbag2/component_player.cpp b/rosbag2/src/rosbag2/composable_player.cpp similarity index 97% rename from rosbag2/src/rosbag2/component_player.cpp rename to rosbag2/src/rosbag2/composable_player.cpp index 5af1114126..37bcb90f40 100644 --- a/rosbag2/src/rosbag2/component_player.cpp +++ b/rosbag2/src/rosbag2/composable_player.cpp @@ -20,7 +20,7 @@ */ #include "rclcpp_components/register_node_macro.hpp" -#include "rosbag2/component_player.hpp" +#include "rosbag2/composable_player.hpp" namespace rosbag2 { From 8751ebf56a3167e3542d5abd3e781d6eb42f3feb Mon Sep 17 00:00:00 2001 From: Michael Orlov Date: Tue, 10 Dec 2024 14:06:43 -0800 Subject: [PATCH 4/4] Add deprecation notice for the rosbag2_transport::Player constructor Signed-off-by: Michael Orlov --- rosbag2_transport/include/rosbag2_transport/player.hpp | 5 ++++- rosbag2_transport/src/rosbag2_transport/player.cpp | 7 ++++++- 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/rosbag2_transport/include/rosbag2_transport/player.hpp b/rosbag2_transport/include/rosbag2_transport/player.hpp index d240d72761..fa260d0057 100644 --- a/rosbag2_transport/include/rosbag2_transport/player.hpp +++ b/rosbag2_transport/include/rosbag2_transport/player.hpp @@ -86,11 +86,14 @@ class Player : public rclcpp::Node /// Will call Player(node_name, node_options) constructor with node_name = "rosbag2_player". /// \param node_options Node options which will be used during construction of the underlying /// node. + [[deprecated("The rosbag2_transport::Player constructor for the composable player is deprecated." + "Please use rosbag2::Player constructor instead")]] ROSBAG2_TRANSPORT_PUBLIC explicit Player(const rclcpp::NodeOptions & node_options); /// \brief Default constructor and entry point for the composable player. - /// Will construct Player class and initialize play_options, storage_options from node + /// \note Uses from the rosbag2::Player constructor which is registered with ament resource index. + /// \details Will construct Player class and initialize play_options, storage_options from node /// parameters. At the end will call Player::play() to automatically start playback in a /// separate thread. /// \param node_name Name for the underlying node. diff --git a/rosbag2_transport/src/rosbag2_transport/player.cpp b/rosbag2_transport/src/rosbag2_transport/player.cpp index 1547eba4d3..2efbb358a9 100644 --- a/rosbag2_transport/src/rosbag2_transport/player.cpp +++ b/rosbag2_transport/src/rosbag2_transport/player.cpp @@ -1689,7 +1689,12 @@ const rosbag2_transport::PlayOptions & PlayerImpl::get_play_options() // Player public interface Player::Player(const rclcpp::NodeOptions & node_options) -: Player("rosbag2_player", node_options) {} +: Player("rosbag2_player", node_options) +{ + RCLCPP_WARN(this->get_logger(), + "The rosbag2_transport::Player composable node is deprecated." + " Please use rosbag2::Player instead"); +} Player::Player(const std::string & node_name, const rclcpp::NodeOptions & node_options) : rclcpp::Node(node_name, node_options)