diff --git a/test_communication/CMakeLists.txt b/test_communication/CMakeLists.txt index f2062b88..4b7a98dd 100644 --- a/test_communication/CMakeLists.txt +++ b/test_communication/CMakeLists.txt @@ -26,8 +26,11 @@ ament_auto_find_build_dependencies() if(BUILD_TESTING) find_package(ament_cmake REQUIRED) - find_package(test_msgs REQUIRED) find_package(osrf_testing_tools_cpp REQUIRED) + find_package(rcpputils REQUIRED) + find_package(rcl REQUIRED) + find_package(rclcpp REQUIRED) + find_package(test_msgs REQUIRED) ament_index_get_resource(interface_files "rosidl_interfaces" "test_msgs") string(REPLACE "\n" ";" interface_files "${interface_files}") @@ -57,6 +60,8 @@ if(BUILD_TESTING) set(other_message_files "msg/FieldsWithSameType.msg" + "msg/Inner.msg" + "msg/Outer.msg" "msg/UInt32.msg" ) rosidl_generate_interfaces(${PROJECT_NAME} @@ -428,7 +433,7 @@ if(BUILD_TESTING) # publisher combined with a subscriber custom_executable(test_publisher_subscriber_cpp "test/test_publisher_subscriber.cpp") - target_link_libraries(test_publisher_subscriber_cpp subscribe_types) + target_link_libraries(test_publisher_subscriber_cpp subscribe_types rcpputils::rcpputils) # subcription valid data custom_executable(test_subscription_valid_data_cpp "test/test_subscription_valid_data.cpp") @@ -449,6 +454,11 @@ if(BUILD_TESTING) custom_executable(test_action_server_cpp "test/test_action_server.cpp") + # Regression test for https://github.com/ros2/rmw_fastrtps/issues/715 + custom_executable(test_nested_types + "test/test_nested_types.cpp") + target_link_libraries(test_nested_types rcpputils::rcpputils) + macro(targets) if(NOT SKIP_SINGLE_RMW_TESTS) custom_test_c(test_messages_c @@ -458,6 +468,8 @@ if(BUILD_TESTING) custom_test(test_publisher_subscriber_cpp TRUE) # subcription valid data custom_test(test_subscription_valid_data_cpp FALSE) + # Regression test for https://github.com/ros2/rmw_fastrtps/issues/715 + custom_test(test_nested_types FALSE) endif() set(rmw_implementation1 "${rmw_implementation}") diff --git a/test_communication/msg/Inner.msg b/test_communication/msg/Inner.msg new file mode 100644 index 00000000..7d6a4971 --- /dev/null +++ b/test_communication/msg/Inner.msg @@ -0,0 +1,3 @@ +# Regression test for https://github.com/ros2/rmw_fastrtps/issues/715 +float64 float_field +bool bool_field diff --git a/test_communication/msg/Outer.msg b/test_communication/msg/Outer.msg new file mode 100644 index 00000000..0d37043b --- /dev/null +++ b/test_communication/msg/Outer.msg @@ -0,0 +1,5 @@ +# Regression test for https://github.com/ros2/rmw_fastrtps/issues/715 +test_communication/Inner inner +bool bool_field_1 +bool bool_field_2 +bool bool_field_3 diff --git a/test_communication/test/test_nested_types.cpp b/test_communication/test/test_nested_types.cpp new file mode 100644 index 00000000..753d52f7 --- /dev/null +++ b/test_communication/test/test_nested_types.cpp @@ -0,0 +1,91 @@ +// Copyright 2023 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. + +// Regression test for https://github.com/ros2/rmw_fastrtps/issues/715 + +#include +#include +#include + +#include "rclcpp/rclcpp.hpp" + +#include "rcpputils/scope_exit.hpp" + +#include "test_communication/msg/outer.hpp" + +template +static typename std::enable_if::is_integer, bool>::type +almost_equal(T x, T y, int ulp) +{ + // the machine epsilon has to be scaled to the magnitude of the values used + // and multiplied by the desired precision in ULPs (units in the last place) + return std::fabs(x - y) <= std::numeric_limits::epsilon() * std::fabs(x + y) * ulp + // unless the result is subnormal + || std::fabs(x - y) < std::numeric_limits::min(); +} + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + RCPPUTILS_SCOPE_EXIT( + { + rclcpp::shutdown(); + }); + + auto node = rclcpp::Node::make_shared("test_nested_types"); + + std::thread spin_thread([node]() { + rclcpp::spin(node); + }); + + bool valid = false; + bool received = false; + auto callback = [&valid, &received](const test_communication::msg::Outer & msg) { + if (almost_equal(msg.inner.float_field, 1.23456789, 2) && + msg.inner.bool_field && msg.bool_field_1 && msg.bool_field_2 && msg.bool_field_3) + { + valid = true; + } + + received = true; + }; + auto subscription = + node->create_subscription("nested_type_topic", 10, callback); + + auto publisher = node->create_publisher("nested_type_topic", 10); + + auto start = std::chrono::steady_clock::now(); + rclcpp::WallRate cycle_rate(20); + while (!received && ((std::chrono::steady_clock::now() - start) < std::chrono::seconds(10))) { + auto msg = test_communication::msg::Outer(); + msg.inner.float_field = 1.23456789; + msg.inner.bool_field = true; + msg.bool_field_1 = true; + msg.bool_field_2 = true; + msg.bool_field_3 = true; + publisher->publish(msg); + + cycle_rate.sleep(); + } + + rclcpp::shutdown(); + + spin_thread.join(); + + if (valid) { + return 0; + } else { + return 1; + } +}