|
14 | 14 |
|
15 | 15 | #include <gtest/gtest.h> |
16 | 16 |
|
| 17 | +#include <future> |
17 | 18 | #include <chrono> |
18 | 19 | #include <memory> |
19 | 20 | #include <string> |
@@ -725,11 +726,7 @@ TEST_F(TestPublisher, intra_process_transient_local) { |
725 | 726 | auto do_nothing = [](std::shared_ptr<const test_msgs::msg::Empty>) {}; |
726 | 727 | struct IntraProcessCallback |
727 | 728 | { |
728 | | - void callback_fun(size_t s) |
729 | | - { |
730 | | - (void) s; |
731 | | - called = true; |
732 | | - } |
| 729 | + void callback_fun(size_t) {called = true;} |
733 | 730 | bool called = false; |
734 | 731 | }; |
735 | 732 | rclcpp::SubscriptionOptions sub_options_ipm_disabled; |
@@ -786,3 +783,44 @@ TEST_F(TestPublisher, intra_process_transient_local) { |
786 | 783 | EXPECT_FALSE(callback3.called); |
787 | 784 | EXPECT_FALSE(callback4.called); |
788 | 785 | } |
| 786 | + |
| 787 | +TEST_F(TestPublisher, intra_process_inter_process_mix_transient_local) { |
| 788 | + constexpr auto history_depth = 10u; |
| 789 | + initialize(rclcpp::NodeOptions().use_intra_process_comms(true)); |
| 790 | + |
| 791 | + rclcpp::PublisherOptionsWithAllocator<std::allocator<void>> pub_options_ipm_enabled; |
| 792 | + pub_options_ipm_enabled.use_intra_process_comm = rclcpp::IntraProcessSetting::Enable; |
| 793 | + |
| 794 | + auto pub_ipm_enabled_transient_local_enabled = node->create_publisher<test_msgs::msg::Empty>( |
| 795 | + "topic1", |
| 796 | + rclcpp::QoS(rclcpp::KeepLast(history_depth)).transient_local(), pub_options_ipm_enabled); |
| 797 | + |
| 798 | + test_msgs::msg::Empty msg; |
| 799 | + pub_ipm_enabled_transient_local_enabled->publish(msg); |
| 800 | + |
| 801 | + auto do_nothing = [](std::shared_ptr<const test_msgs::msg::Empty>) {}; |
| 802 | + struct SubscriptionCallback |
| 803 | + { |
| 804 | + void callback_fun(size_t) {called.set_value();} |
| 805 | + std::promise<void> called; |
| 806 | + }; |
| 807 | + rclcpp::SubscriptionOptions sub_options_ipm_disabled; |
| 808 | + sub_options_ipm_disabled.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable; |
| 809 | + SubscriptionCallback intra_callback, inter_callback; |
| 810 | + std::future<void> intra_callback_future = intra_callback.called.get_future(), |
| 811 | + inter_callback_future = inter_callback.called.get_future(); |
| 812 | + auto sub_ipm_disabled_transient_local_enabled = node->create_subscription<test_msgs::msg::Empty>( |
| 813 | + "topic1", |
| 814 | + rclcpp::QoS(rclcpp::KeepLast(history_depth)).transient_local(), |
| 815 | + do_nothing, sub_options_ipm_disabled); |
| 816 | + sub_ipm_disabled_transient_local_enabled->set_on_new_intra_process_message_callback( |
| 817 | + std::bind(&SubscriptionCallback::callback_fun, &intra_callback, std::placeholders::_1)); |
| 818 | + sub_ipm_disabled_transient_local_enabled->set_on_new_message_callback( |
| 819 | + std::bind(&SubscriptionCallback::callback_fun, &inter_callback, std::placeholders::_1)); |
| 820 | + rclcpp::executors::SingleThreadedExecutor executor; |
| 821 | + executor.add_node(node); |
| 822 | + EXPECT_EQ(executor.spin_until_future_complete(inter_callback_future, |
| 823 | + std::chrono::milliseconds(100)), rclcpp::FutureReturnCode::SUCCESS); |
| 824 | + EXPECT_EQ(executor.spin_until_future_complete(intra_callback_future, |
| 825 | + std::chrono::milliseconds(100)), rclcpp::FutureReturnCode::TIMEOUT); |
| 826 | +} |
0 commit comments