Skip to content

Commit

Permalink
Make Player a rosbag2 component
Browse files Browse the repository at this point in the history
Signed-off-by: Patrick Roncagliolo <[email protected]>
  • Loading branch information
roncapat committed Dec 9, 2024
1 parent 34ccb39 commit 7a80a0e
Show file tree
Hide file tree
Showing 2 changed files with 72 additions and 0 deletions.
58 changes: 58 additions & 0 deletions rosbag2/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -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()
14 changes: 14 additions & 0 deletions rosbag2/src/rosbag2/component_player.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
#include "rosbag2_transport/player.hpp"

Check failure on line 1 in rosbag2/src/rosbag2/component_player.cpp

View workflow job for this annotation

GitHub Actions / ament_copyright

could not find copyright notice

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)

0 comments on commit 7a80a0e

Please sign in to comment.