diff --git a/rosbag2_py/CMakeLists.txt b/rosbag2_py/CMakeLists.txt index 97e74f24f..feb07925f 100644 --- a/rosbag2_py/CMakeLists.txt +++ b/rosbag2_py/CMakeLists.txt @@ -48,6 +48,13 @@ target_link_libraries(_compression_options PUBLIC rosbag2_compression::rosbag2_compression ) +pybind11_add_module(_message_definitions SHARED + src/rosbag2_py/_message_definitions.cpp +) +target_link_libraries(_message_definitions PUBLIC + rosbag2_cpp::rosbag2_cpp +) + pybind11_add_module(_reader SHARED src/rosbag2_py/_reader.cpp ) @@ -107,6 +114,7 @@ target_link_libraries(_reindexer PUBLIC install( TARGETS _compression_options + _message_definitions _reader _storage _writer @@ -120,6 +128,7 @@ if(BUILD_TESTING) find_package(ament_lint_auto REQUIRED) ament_lint_auto_find_test_dependencies() find_package(ament_cmake_pytest REQUIRED) + find_package(rosbag2_test_msgdefs REQUIRED) set(append_env_vars "PYTHONPATH=${CMAKE_CURRENT_SOURCE_DIR}") set(set_env_vars "ROSBAG2_PY_TEST_RESOURCES_DIR=${CMAKE_CURRENT_SOURCE_DIR}/test/resources") @@ -169,6 +178,11 @@ if(BUILD_TESTING) APPEND_ENV "${append_env_vars}" ENV "${set_env_vars}" ) + ament_add_pytest_test(test_message_definitions_py + "test/test_message_definitions.py" + APPEND_ENV "${append_env_vars}" + ENV "${set_env_vars}" + ) endif() ament_package() diff --git a/rosbag2_py/package.xml b/rosbag2_py/package.xml index ed2901f9a..2bee37ff6 100644 --- a/rosbag2_py/package.xml +++ b/rosbag2_py/package.xml @@ -36,6 +36,7 @@ rosbag2_test_common rosidl_runtime_py std_msgs + rosbag2_test_msgdefs ament_cmake diff --git a/rosbag2_py/rosbag2_py/__init__.py b/rosbag2_py/rosbag2_py/__init__.py index 6f084da50..47d6c20d7 100644 --- a/rosbag2_py/rosbag2_py/__init__.py +++ b/rosbag2_py/rosbag2_py/__init__.py @@ -24,6 +24,9 @@ compression_mode_from_string, compression_mode_to_string ) + from rosbag2_py._message_definitions import ( + LocalMessageDefinitionSource, + ) from rosbag2_py._reader import ( SequentialCompressionReader, SequentialReader, @@ -100,4 +103,5 @@ 'ServiceRequestsSource', 'Recorder', 'RecordOptions', + 'LocalMessageDefinitionSource', ] diff --git a/rosbag2_py/rosbag2_py/__init__.pyi b/rosbag2_py/rosbag2_py/__init__.pyi index a6ed335a1..c9a51d1cb 100644 --- a/rosbag2_py/rosbag2_py/__init__.pyi +++ b/rosbag2_py/rosbag2_py/__init__.pyi @@ -1,5 +1,6 @@ from rosbag2_py._compression_options import CompressionMode as CompressionMode, CompressionOptions as CompressionOptions, compression_mode_from_string as compression_mode_from_string, compression_mode_to_string as compression_mode_to_string from rosbag2_py._info import Info as Info +from rosbag2_py._message_definitions import LocalMessageDefinitionSource as LocalMessageDefinitionSource from rosbag2_py._reader import SequentialCompressionReader as SequentialCompressionReader, SequentialReader as SequentialReader, get_registered_readers as get_registered_readers from rosbag2_py._reindexer import Reindexer as Reindexer from rosbag2_py._storage import BagMetadata as BagMetadata, ConverterOptions as ConverterOptions, FileInformation as FileInformation, MessageDefinition as MessageDefinition, MetadataIo as MetadataIo, ReadOrder as ReadOrder, ReadOrderSortBy as ReadOrderSortBy, StorageFilter as StorageFilter, StorageOptions as StorageOptions, TopicInformation as TopicInformation, TopicMetadata as TopicMetadata, get_default_storage_id as get_default_storage_id, to_rclcpp_qos_vector as to_rclcpp_qos_vector diff --git a/rosbag2_py/rosbag2_py/_message_definitions.pyi b/rosbag2_py/rosbag2_py/_message_definitions.pyi new file mode 100644 index 000000000..e45e83187 --- /dev/null +++ b/rosbag2_py/rosbag2_py/_message_definitions.pyi @@ -0,0 +1,5 @@ +from typing import Any + +class LocalMessageDefinitionSource: + def __init__(self) -> None: ... + def get_full_text(self, *args, **kwargs) -> Any: ... diff --git a/rosbag2_py/src/rosbag2_py/_message_definitions.cpp b/rosbag2_py/src/rosbag2_py/_message_definitions.cpp new file mode 100644 index 000000000..44d04f761 --- /dev/null +++ b/rosbag2_py/src/rosbag2_py/_message_definitions.cpp @@ -0,0 +1,27 @@ +// Copyright 2024 Intrinsic Innovation LLC. All rights reserved. +// +// 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. + +#include "rosbag2_cpp/message_definitions/local_message_definition_source.hpp" + +#include "./pybind11.hpp" + +PYBIND11_MODULE(_message_definitions, m) { + m.doc() = "Python wrapper of the rosbag2_cpp message definitions API"; + + pybind11::class_( + m, "LocalMessageDefinitionSource") + .def(pybind11::init<>()) + .def( + "get_full_text", &rosbag2_cpp::LocalMessageDefinitionSource::get_full_text); +} diff --git a/rosbag2_py/test/test_message_definitions.py b/rosbag2_py/test/test_message_definitions.py new file mode 100644 index 000000000..3863fa0b8 --- /dev/null +++ b/rosbag2_py/test/test_message_definitions.py @@ -0,0 +1,146 @@ +# Copyright 2024 Intrinsic Innovation LLC. All rights reserved. +# +# 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. + +from rosbag2_py import LocalMessageDefinitionSource + + +def test_local_message_definition_source_no_crash_on_bad_name(): + source = LocalMessageDefinitionSource() + result = source.get_full_text('some_pkg') + assert result.encoding == 'unknown' + assert result.encoded_message_definition == '' + assert result.topic_type == 'some_pkg' + + +def test_local_message_definition_source_can_find_msg_deps(): + source = LocalMessageDefinitionSource() + result = source.get_full_text('rosbag2_test_msgdefs/ComplexMsg') + assert result.encoding == 'ros2msg' + assert result.encoded_message_definition == ( + 'rosbag2_test_msgdefs/BasicMsg b\n' + '\n' + '================================================================================\n' + 'MSG: rosbag2_test_msgdefs/BasicMsg\n' + 'float32 c\n' + ) + + +def test_local_message_definition_source_can_find_srv_deps_in_msg(): + source = LocalMessageDefinitionSource() + result = source.get_full_text('rosbag2_test_msgdefs/srv/ComplexSrvMsg') + assert result.encoding == 'ros2msg' + assert result.topic_type == 'rosbag2_test_msgdefs/srv/ComplexSrvMsg' + assert result.encoded_message_definition == ( + '================================================================================\n' + 'SRV: rosbag2_test_msgdefs/srv/ComplexSrvMsg\n' + 'rosbag2_test_msgdefs/BasicMsg req\n' + '---\n' + 'rosbag2_test_msgdefs/BasicMsg resp\n' + '\n' + '================================================================================\n' + 'MSG: rosbag2_test_msgdefs/BasicMsg\n' + 'float32 c\n' + ) + + +def test_local_message_definition_source_can_find_srv_deps_in_idl(): + source = LocalMessageDefinitionSource() + result = source.get_full_text('rosbag2_test_msgdefs/srv/ComplexSrvIdl') + assert result.encoding == 'ros2idl' + assert result.topic_type == 'rosbag2_test_msgdefs/srv/ComplexSrvIdl' + assert result.encoded_message_definition == ( + '================================================================================\n' + 'SRV: rosbag2_test_msgdefs/srv/ComplexSrvIdl\n' + 'rosbag2_test_msgdefs/BasicIdl req\n' + '---\n' + 'rosbag2_test_msgdefs/BasicIdl resp\n' + '\n' + '================================================================================\n' + 'MSG: rosbag2_test_msgdefs/BasicIdl\n' + '\n' + '================================================================================\n' + 'IDL: rosbag2_test_msgdefs/BasicIdl\n' + 'module rosbag2_test_msgdefs {\n' + ' module msg {\n' + ' struct BasicIdl {\n' + ' float x;\n' + ' };\n' + ' };\n' + '};\n' + ) + + +def test_local_message_definition_source_can_find_idl_deps(): + source = LocalMessageDefinitionSource() + result = source.get_full_text('rosbag2_test_msgdefs/msg/ComplexIdl') + assert result.encoding == 'ros2idl' + assert result.topic_type == 'rosbag2_test_msgdefs/msg/ComplexIdl' + assert result.encoded_message_definition == ( + '================================================================================\n' + 'IDL: rosbag2_test_msgdefs/msg/ComplexIdl\n' + '#include "rosbag2_test_msgdefs/msg/BasicIdl.idl"\n' + '\n' + 'module rosbag2_test_msgdefs {\n' + ' module msg {\n' + ' struct ComplexIdl {\n' + ' rosbag2_test_msgdefs::msg::BasicIdl a;\n' + ' };\n' + ' };\n' + '};\n' + '\n' + '================================================================================\n' + 'IDL: rosbag2_test_msgdefs/msg/BasicIdl\n' + 'module rosbag2_test_msgdefs {\n' + ' module msg {\n' + ' struct BasicIdl {\n' + ' float x;\n' + ' };\n' + ' };\n' + '};\n' + ) + + +def test_local_message_definition_source_can_resolve_msg_with_idl_deps(): + source = LocalMessageDefinitionSource() + result = source.get_full_text( + 'rosbag2_test_msgdefs/msg/ComplexMsgDependsOnIdl') + assert result.encoding == 'ros2idl' + assert result.topic_type == 'rosbag2_test_msgdefs/msg/ComplexMsgDependsOnIdl' + assert result.encoded_message_definition == ( + '================================================================================\n' + 'IDL: rosbag2_test_msgdefs/msg/ComplexMsgDependsOnIdl\n' + '// generated from rosidl_adapter/resource/msg.idl.em\n' + '// with input from rosbag2_test_msgdefs/msg/ComplexMsgDependsOnIdl.msg\n' + '// generated code does not contain a copyright notice\n' + '\n' + '#include "rosbag2_test_msgdefs/msg/BasicIdl.idl"\n' + '\n' + 'module rosbag2_test_msgdefs {\n' + ' module msg {\n' + ' struct ComplexMsgDependsOnIdl {\n' + ' rosbag2_test_msgdefs::msg::BasicIdl a;\n' + ' };\n' + ' };\n' + '};\n' + '\n' + '================================================================================\n' + 'IDL: rosbag2_test_msgdefs/msg/BasicIdl\n' + 'module rosbag2_test_msgdefs {\n' + ' module msg {\n' + ' struct BasicIdl {\n' + ' float x;\n' + ' };\n' + ' };\n' + '};\n' + )