|
14 | 14 |
|
15 | 15 | #include <gtest/gtest.h> |
16 | 16 |
|
17 | | -#include "rcl/rcl.h" |
| 17 | +#include "osrf_testing_tools_cpp/scope_exit.hpp" |
| 18 | + |
18 | 19 | #include "rcl/discovery_options.h" |
| 20 | +#include "rcl/rcl.h" |
19 | 21 |
|
20 | 22 | #include "rcutils/allocator.h" |
21 | 23 | #include "rcutils/env.h" |
22 | 24 |
|
23 | 25 | #include "rmw/discovery_options.h" |
24 | 26 |
|
| 27 | +#include "../src/rcl/context_impl.h" |
| 28 | +#include "../src/rcl/init_options_impl.h" |
| 29 | + |
| 30 | +void check_discovery( |
| 31 | + rmw_automatic_discovery_range_t discovery_range, |
| 32 | + size_t static_peer_count) |
| 33 | +{ |
| 34 | + rcl_ret_t ret; |
| 35 | + rcl_init_options_t init_options = rcl_get_zero_initialized_init_options(); |
| 36 | + ret = rcl_init_options_init(&init_options, rcl_get_default_allocator()); |
| 37 | + ASSERT_EQ(RCL_RET_OK, ret); |
| 38 | + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( |
| 39 | + { |
| 40 | + EXPECT_EQ(RCL_RET_OK, rcl_init_options_fini(&init_options)); |
| 41 | + }); |
| 42 | + rcl_context_t context = rcl_get_zero_initialized_context(); |
| 43 | + ret = rcl_init(0, nullptr, &init_options, &context); |
| 44 | + ASSERT_EQ(RCL_RET_OK, ret); |
| 45 | + OSRF_TESTING_TOOLS_CPP_SCOPE_EXIT( |
| 46 | + { |
| 47 | + ASSERT_EQ(RCL_RET_OK, rcl_shutdown(&context)); |
| 48 | + ASSERT_EQ(RCL_RET_OK, rcl_context_fini(&context)); |
| 49 | + }); |
| 50 | + rmw_discovery_options_t * discovery_options = |
| 51 | + &context.impl->init_options.impl->rmw_init_options.discovery_options; |
| 52 | + EXPECT_EQ(discovery_range, discovery_options->automatic_discovery_range); |
| 53 | + EXPECT_EQ(static_peer_count, discovery_options->static_peers_count); |
| 54 | +} |
| 55 | + |
25 | 56 | TEST(TestDiscoveryInfo, test_get_peers) { |
26 | 57 | rcutils_allocator_t allocator = rcutils_get_default_allocator(); |
27 | 58 | rmw_discovery_options_t discovery_options_var = rmw_get_zero_initialized_discovery_options(); |
@@ -241,3 +272,49 @@ TEST(TestDiscoveryInfo, test_get_both) { |
241 | 272 | EXPECT_EQ(0u, discovery_options_var.static_peers_count); |
242 | 273 | EXPECT_EQ(RCL_RET_OK, rmw_discovery_options_fini(&discovery_options_var)); |
243 | 274 | } |
| 275 | + |
| 276 | +// localhost_only is deprecated but still honored to prevail discovery_options. |
| 277 | +// see https://github.com/ros2/ros2_documentation/pull/3519#discussion_r1186541935 |
| 278 | +// TODO(fujitatomoya): remove localhost_only completely after deprecation period. |
| 279 | +TEST(TestDiscoveryInfo, test_with_localhost_only) { |
| 280 | + { |
| 281 | + // No environment variable set (default subnet, no specific peers) |
| 282 | + check_discovery(RMW_AUTOMATIC_DISCOVERY_RANGE_SUBNET, 0); |
| 283 | + } |
| 284 | + |
| 285 | + { |
| 286 | + // only ROS_AUTOMATIC_DISCOVERY_RANGE and ROS_STATIC_PEERS set |
| 287 | + ASSERT_TRUE(rcutils_set_env("ROS_AUTOMATIC_DISCOVERY_RANGE", "LOCALHOST")); |
| 288 | + ASSERT_TRUE(rcutils_set_env("ROS_STATIC_PEERS", "127.0.0.1;localhost.com")); |
| 289 | + check_discovery(RMW_AUTOMATIC_DISCOVERY_RANGE_LOCALHOST, 2); |
| 290 | + } |
| 291 | + |
| 292 | + { |
| 293 | + // Only ROS_LOCALHOST_ONLY is enabled |
| 294 | + ASSERT_TRUE(rcutils_set_env("ROS_LOCALHOST_ONLY", "1")); |
| 295 | + check_discovery(RMW_AUTOMATIC_DISCOVERY_RANGE_LOCALHOST, 0); |
| 296 | + } |
| 297 | + |
| 298 | + { |
| 299 | + // ROS_LOCALHOST_ONLY is enabled and prevails over SUBNET. |
| 300 | + ASSERT_TRUE(rcutils_set_env("ROS_LOCALHOST_ONLY", "1")); |
| 301 | + ASSERT_TRUE(rcutils_set_env("ROS_AUTOMATIC_DISCOVERY_RANGE", "SUBNET")); |
| 302 | + ASSERT_TRUE(rcutils_set_env("ROS_STATIC_PEERS", "192.168.0.1;remote.com")); |
| 303 | + check_discovery(RMW_AUTOMATIC_DISCOVERY_RANGE_LOCALHOST, 0); |
| 304 | + } |
| 305 | + |
| 306 | + { |
| 307 | + // ROS_LOCALHOST_ONLY is enabled and prevails over OFF. |
| 308 | + ASSERT_TRUE(rcutils_set_env("ROS_LOCALHOST_ONLY", "1")); |
| 309 | + ASSERT_TRUE(rcutils_set_env("ROS_AUTOMATIC_DISCOVERY_RANGE", "OFF")); |
| 310 | + check_discovery(RMW_AUTOMATIC_DISCOVERY_RANGE_LOCALHOST, 0); |
| 311 | + } |
| 312 | + |
| 313 | + { |
| 314 | + // ROS_LOCALHOST_ONLY is disabled, falls down to use discovery option. |
| 315 | + ASSERT_TRUE(rcutils_set_env("ROS_LOCALHOST_ONLY", "0")); |
| 316 | + ASSERT_TRUE(rcutils_set_env("ROS_AUTOMATIC_DISCOVERY_RANGE", "SUBNET")); |
| 317 | + ASSERT_TRUE(rcutils_set_env("ROS_STATIC_PEERS", "192.168.0.1;remote.com")); |
| 318 | + check_discovery(RMW_AUTOMATIC_DISCOVERY_RANGE_SUBNET, 2); |
| 319 | + } |
| 320 | +} |
0 commit comments