Skip to content

Commit

Permalink
Add integration test for nested messages. (#530)
Browse files Browse the repository at this point in the history
Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Oct 4, 2023
1 parent 6b89236 commit c9569c1
Show file tree
Hide file tree
Showing 4 changed files with 113 additions and 2 deletions.
16 changes: 14 additions & 2 deletions test_communication/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -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}")
Expand Down Expand Up @@ -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}
Expand Down Expand Up @@ -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")
Expand All @@ -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
Expand All @@ -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}")
Expand Down
3 changes: 3 additions & 0 deletions test_communication/msg/Inner.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
# Regression test for https://github.com/ros2/rmw_fastrtps/issues/715
float64 float_field
bool bool_field
5 changes: 5 additions & 0 deletions test_communication/msg/Outer.msg
Original file line number Diff line number Diff line change
@@ -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
91 changes: 91 additions & 0 deletions test_communication/test/test_nested_types.cpp
Original file line number Diff line number Diff line change
@@ -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 <chrono>
#include <limits>
#include <thread>

#include "rclcpp/rclcpp.hpp"

#include "rcpputils/scope_exit.hpp"

#include "test_communication/msg/outer.hpp"

template<class T>
static typename std::enable_if<!std::numeric_limits<T>::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<T>::epsilon() * std::fabs(x + y) * ulp
// unless the result is subnormal
|| std::fabs(x - y) < std::numeric_limits<T>::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<test_communication::msg::Outer>("nested_type_topic", 10, callback);

auto publisher = node->create_publisher<test_communication::msg::Outer>("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;
}
}

0 comments on commit c9569c1

Please sign in to comment.