Skip to content

Commit 101e406

Browse files
authored
localhost_only prevails auto discovery options if enabled. (ros2#1069)
* localhost_only prevails auto discovery options if enabled. Signed-off-by: Tomoya Fujita <[email protected]>
1 parent c0bf923 commit 101e406

File tree

3 files changed

+131
-33
lines changed

3 files changed

+131
-33
lines changed

rcl/src/rcl/init.c

Lines changed: 52 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -159,8 +159,8 @@ rcl_init(
159159
if (RMW_LOCALHOST_ONLY_DEFAULT != *localhost_only) {
160160
RCUTILS_LOG_WARN_NAMED(
161161
ROS_PACKAGE_NAME,
162-
"'localhost_only' init option is deprecated. Use 'automatic_discovery_range' and "
163-
"'static_peers' instead.");
162+
"'localhost_only' init option is deprecated but still honored if it is enabled. "
163+
"Use 'automatic_discovery_range' and 'static_peers' instead.");
164164
} else {
165165
// Get actual localhost_only value based on environment variable, if needed.
166166
ret = rcl_get_localhost_only(localhost_only);
@@ -171,8 +171,8 @@ rcl_init(
171171
if (RMW_LOCALHOST_ONLY_DEFAULT != *localhost_only) {
172172
RCUTILS_LOG_WARN_NAMED(
173173
ROS_PACKAGE_NAME,
174-
"ROS_LOCALHOST_ONLY is deprecated. Use ROS_AUTOMATIC_DISCOVERY_RANGE and "
175-
"ROS_STATIC_PEERS instead.");
174+
"ROS_LOCALHOST_ONLY is deprecated but still honored if it is enabled. "
175+
"Use ROS_AUTOMATIC_DISCOVERY_RANGE and ROS_STATIC_PEERS instead.");
176176
}
177177
}
178178

@@ -181,38 +181,58 @@ rcl_init(
181181
rmw_discovery_options_t * discovery_options =
182182
&context->impl->init_options.impl->rmw_init_options.discovery_options;
183183

184-
// Get actual discovery range option based on environment variable, if not given
185-
// to original options passed to function
186-
if ( // NOLINT
187-
RMW_AUTOMATIC_DISCOVERY_RANGE_NOT_SET == original_discovery_options.automatic_discovery_range)
188-
{
189-
ret = rcl_get_automatic_discovery_range(discovery_options);
190-
if (RCL_RET_OK != ret) {
191-
fail_ret = ret;
192-
goto fail;
184+
// this happens either rmw implementation forces or via environmental variable.
185+
// localhost_only is deprecated but still honored to prevail discovery_options.
186+
// see https://github.com/ros2/ros2_documentation/pull/3519#discussion_r1186541935
187+
// TODO(fujitatomoya): remove localhost_only completely after deprecation period.
188+
if (*localhost_only == RMW_LOCALHOST_ONLY_ENABLED) {
189+
RCUTILS_LOG_WARN_NAMED(
190+
ROS_PACKAGE_NAME,
191+
"'localhost_only' is enabled, "
192+
"'automatic_discovery_range' and 'static_peers' will be ignored.");
193+
discovery_options->automatic_discovery_range = RMW_AUTOMATIC_DISCOVERY_RANGE_LOCALHOST;
194+
discovery_options->static_peers_count = 0;
195+
} else {
196+
if (*localhost_only == RMW_LOCALHOST_ONLY_DISABLED) {
197+
RCUTILS_LOG_WARN_NAMED(
198+
ROS_PACKAGE_NAME,
199+
"'localhost_only' is disabled, "
200+
"'automatic_discovery_range' and 'static_peers' will be used.");
193201
}
194-
}
195202

196-
if (0 == discovery_options->static_peers_count &&
197-
discovery_options->automatic_discovery_range != RMW_AUTOMATIC_DISCOVERY_RANGE_OFF)
198-
{
199-
// Get static peers.
200-
// If off is set, it makes sense to not get any static peers.
201-
ret = rcl_get_discovery_static_peers(discovery_options, &allocator);
202-
if (RCL_RET_OK != ret) {
203-
fail_ret = ret;
204-
goto fail;
203+
// Get actual discovery range option based on environment variable, if not given
204+
// to original options passed to function
205+
if ( // NOLINT
206+
RMW_AUTOMATIC_DISCOVERY_RANGE_NOT_SET == original_discovery_options.automatic_discovery_range)
207+
{
208+
ret = rcl_get_automatic_discovery_range(discovery_options);
209+
if (RCL_RET_OK != ret) {
210+
fail_ret = ret;
211+
goto fail;
212+
}
205213
}
206-
}
207214

208-
if (discovery_options->static_peers_count > 0 &&
209-
discovery_options->automatic_discovery_range == RMW_AUTOMATIC_DISCOVERY_RANGE_OFF)
210-
{
211-
RCUTILS_LOG_WARN_NAMED(
212-
ROS_PACKAGE_NAME,
213-
"Note: ROS_AUTOMATIC_DISCOVERY_RANGE is set to OFF, but "
214-
"found static peers in ROS_STATIC_PEERS. "
215-
"ROS_STATIC_PEERS will be ignored.");
215+
if (0 == discovery_options->static_peers_count &&
216+
discovery_options->automatic_discovery_range != RMW_AUTOMATIC_DISCOVERY_RANGE_OFF)
217+
{
218+
// Get static peers.
219+
// If off is set, it makes sense to not get any static peers.
220+
ret = rcl_get_discovery_static_peers(discovery_options, &allocator);
221+
if (RCL_RET_OK != ret) {
222+
fail_ret = ret;
223+
goto fail;
224+
}
225+
}
226+
227+
if (discovery_options->static_peers_count > 0 &&
228+
discovery_options->automatic_discovery_range == RMW_AUTOMATIC_DISCOVERY_RANGE_OFF)
229+
{
230+
RCUTILS_LOG_WARN_NAMED(
231+
ROS_PACKAGE_NAME,
232+
"Note: ROS_AUTOMATIC_DISCOVERY_RANGE is set to OFF, but "
233+
"found static peers in ROS_STATIC_PEERS. "
234+
"ROS_STATIC_PEERS will be ignored.");
235+
}
216236
}
217237

218238
const char * discovery_range_string =

rcl/test/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -402,6 +402,7 @@ rcl_add_custom_gtest(test_discovery_options
402402
SRCS rcl/test_discovery_options.cpp
403403
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
404404
LIBRARIES ${PROJECT_NAME}
405+
AMENT_DEPENDENCIES "osrf_testing_tools_cpp"
405406
)
406407

407408
rcl_add_custom_gtest(test_domain_id

rcl/test/rcl/test_discovery_options.cpp

Lines changed: 78 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,14 +14,45 @@
1414

1515
#include <gtest/gtest.h>
1616

17-
#include "rcl/rcl.h"
17+
#include "osrf_testing_tools_cpp/scope_exit.hpp"
18+
1819
#include "rcl/discovery_options.h"
20+
#include "rcl/rcl.h"
1921

2022
#include "rcutils/allocator.h"
2123
#include "rcutils/env.h"
2224

2325
#include "rmw/discovery_options.h"
2426

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+
2556
TEST(TestDiscoveryInfo, test_get_peers) {
2657
rcutils_allocator_t allocator = rcutils_get_default_allocator();
2758
rmw_discovery_options_t discovery_options_var = rmw_get_zero_initialized_discovery_options();
@@ -241,3 +272,49 @@ TEST(TestDiscoveryInfo, test_get_both) {
241272
EXPECT_EQ(0u, discovery_options_var.static_peers_count);
242273
EXPECT_EQ(RCL_RET_OK, rmw_discovery_options_fini(&discovery_options_var));
243274
}
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

Comments
 (0)