Skip to content

Commit

Permalink
Removed deprecated localhost_only (#1169)
Browse files Browse the repository at this point in the history
Signed-off-by: Alejandro Hernández Cordero <[email protected]>
  • Loading branch information
ahcorde authored Jul 29, 2024
1 parent 6df1195 commit 9725f91
Show file tree
Hide file tree
Showing 8 changed files with 28 additions and 243 deletions.
1 change: 0 additions & 1 deletion rcl/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,6 @@ set(${PROJECT_NAME}_sources
src/rcl/init_options.c
src/rcl/lexer.c
src/rcl/lexer_lookahead.c
src/rcl/localhost.c
src/rcl/logging_rosout.c
src/rcl/logging.c
src/rcl/log_level.c
Expand Down
48 changes: 0 additions & 48 deletions rcl/include/rcl/localhost.h

This file was deleted.

99 changes: 28 additions & 71 deletions rcl/src/rcl/init.c
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,6 @@ extern "C"
#include "rcl/discovery_options.h"
#include "rcl/domain_id.h"
#include "rcl/error_handling.h"
#include "rcl/localhost.h"
#include "rcl/logging.h"
#include "rcl/security.h"
#include "rcl/validate_enclave_name.h"
Expand Down Expand Up @@ -154,85 +153,43 @@ rcl_init(
}
}

rmw_localhost_only_t * localhost_only =
&context->impl->init_options.impl->rmw_init_options.localhost_only;
if (RMW_LOCALHOST_ONLY_DEFAULT != *localhost_only) {
RCUTILS_LOG_WARN_NAMED(
ROS_PACKAGE_NAME,
"'localhost_only' init option is deprecated but still honored if it is enabled. "
"Use 'automatic_discovery_range' and 'static_peers' instead.");
} else {
// Get actual localhost_only value based on environment variable, if needed.
ret = rcl_get_localhost_only(localhost_only);
if (RCL_RET_OK != ret) {
fail_ret = ret;
goto fail;
}
if (RMW_LOCALHOST_ONLY_DEFAULT != *localhost_only) {
RCUTILS_LOG_WARN_NAMED(
ROS_PACKAGE_NAME,
"ROS_LOCALHOST_ONLY is deprecated but still honored if it is enabled. "
"Use ROS_AUTOMATIC_DISCOVERY_RANGE and ROS_STATIC_PEERS instead.");
}
}

const rmw_discovery_options_t original_discovery_options =
options->impl->rmw_init_options.discovery_options;
rmw_discovery_options_t * discovery_options =
&context->impl->init_options.impl->rmw_init_options.discovery_options;

// this happens either rmw implementation forces or via environmental variable.
// localhost_only is deprecated but still honored to prevail discovery_options.
// see https://github.com/ros2/ros2_documentation/pull/3519#discussion_r1186541935
// TODO(fujitatomoya): remove localhost_only completely after deprecation period.
if (*localhost_only == RMW_LOCALHOST_ONLY_ENABLED) {
RCUTILS_LOG_WARN_NAMED(
ROS_PACKAGE_NAME,
"'localhost_only' is enabled, "
"'automatic_discovery_range' and 'static_peers' will be ignored.");
discovery_options->automatic_discovery_range = RMW_AUTOMATIC_DISCOVERY_RANGE_LOCALHOST;
discovery_options->static_peers_count = 0;
} else {
if (*localhost_only == RMW_LOCALHOST_ONLY_DISABLED) {
RCUTILS_LOG_WARN_NAMED(
ROS_PACKAGE_NAME,
"'localhost_only' is disabled, "
"'automatic_discovery_range' and 'static_peers' will be used.");
}

// Get actual discovery range option based on environment variable, if not given
// to original options passed to function
if ( // NOLINT
RMW_AUTOMATIC_DISCOVERY_RANGE_NOT_SET == original_discovery_options.automatic_discovery_range)
{
ret = rcl_get_automatic_discovery_range(discovery_options);
if (RCL_RET_OK != ret) {
fail_ret = ret;
goto fail;
}
// Get actual discovery range option based on environment variable, if not given
// to original options passed to function
if ( // NOLINT
RMW_AUTOMATIC_DISCOVERY_RANGE_NOT_SET == original_discovery_options.automatic_discovery_range)
{
ret = rcl_get_automatic_discovery_range(discovery_options);
if (RCL_RET_OK != ret) {
fail_ret = ret;
goto fail;
}
}

if (0 == discovery_options->static_peers_count &&
discovery_options->automatic_discovery_range != RMW_AUTOMATIC_DISCOVERY_RANGE_OFF)
{
// Get static peers.
// If off is set, it makes sense to not get any static peers.
ret = rcl_get_discovery_static_peers(discovery_options, &allocator);
if (RCL_RET_OK != ret) {
fail_ret = ret;
goto fail;
}
if (0 == discovery_options->static_peers_count &&
discovery_options->automatic_discovery_range != RMW_AUTOMATIC_DISCOVERY_RANGE_OFF)
{
// Get static peers.
// If off is set, it makes sense to not get any static peers.
ret = rcl_get_discovery_static_peers(discovery_options, &allocator);
if (RCL_RET_OK != ret) {
fail_ret = ret;
goto fail;
}
}

if (discovery_options->static_peers_count > 0 &&
discovery_options->automatic_discovery_range == RMW_AUTOMATIC_DISCOVERY_RANGE_OFF)
{
RCUTILS_LOG_WARN_NAMED(
ROS_PACKAGE_NAME,
"Note: ROS_AUTOMATIC_DISCOVERY_RANGE is set to OFF, but "
"found static peers in ROS_STATIC_PEERS. "
"ROS_STATIC_PEERS will be ignored.");
}
if (discovery_options->static_peers_count > 0 &&
discovery_options->automatic_discovery_range == RMW_AUTOMATIC_DISCOVERY_RANGE_OFF)
{
RCUTILS_LOG_WARN_NAMED(
ROS_PACKAGE_NAME,
"Note: ROS_AUTOMATIC_DISCOVERY_RANGE is set to OFF, but "
"found static peers in ROS_STATIC_PEERS. "
"ROS_STATIC_PEERS will be ignored.");
}

const char * discovery_range_string =
Expand Down
52 changes: 0 additions & 52 deletions rcl/src/rcl/localhost.c

This file was deleted.

1 change: 0 additions & 1 deletion rcl/src/rcl/node.c
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,6 @@
#include "rcl/arguments.h"
#include "rcl/error_handling.h"
#include "rcl/init_options.h"
#include "rcl/localhost.h"
#include "rcl/logging.h"
#include "rcl/logging_rosout.h"
#include "rcl/node_type_cache.h"
Expand Down
6 changes: 0 additions & 6 deletions rcl/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -474,12 +474,6 @@ rcl_add_custom_gtest(test_domain_id
)
ament_add_test_label(test_domain_id mimick)

rcl_add_custom_gtest(test_localhost
SRCS rcl/test_localhost.cpp
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
LIBRARIES ${PROJECT_NAME}
)

rcl_add_custom_gtest(test_logging
SRCS rcl/test_logging.cpp
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
Expand Down
23 changes: 0 additions & 23 deletions rcl/test/rcl/test_discovery_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -293,29 +293,6 @@ TEST(TestDiscoveryInfo, test_with_localhost_only) {
}

{
// Only ROS_LOCALHOST_ONLY is enabled
ASSERT_TRUE(rcutils_set_env("ROS_LOCALHOST_ONLY", "1"));
check_discovery(RMW_AUTOMATIC_DISCOVERY_RANGE_LOCALHOST, 0);
}

{
// ROS_LOCALHOST_ONLY is enabled and prevails over SUBNET.
ASSERT_TRUE(rcutils_set_env("ROS_LOCALHOST_ONLY", "1"));
ASSERT_TRUE(rcutils_set_env("ROS_AUTOMATIC_DISCOVERY_RANGE", "SUBNET"));
ASSERT_TRUE(rcutils_set_env("ROS_STATIC_PEERS", "192.168.0.1;remote.com"));
check_discovery(RMW_AUTOMATIC_DISCOVERY_RANGE_LOCALHOST, 0);
}

{
// ROS_LOCALHOST_ONLY is enabled and prevails over OFF.
ASSERT_TRUE(rcutils_set_env("ROS_LOCALHOST_ONLY", "1"));
ASSERT_TRUE(rcutils_set_env("ROS_AUTOMATIC_DISCOVERY_RANGE", "OFF"));
check_discovery(RMW_AUTOMATIC_DISCOVERY_RANGE_LOCALHOST, 0);
}

{
// ROS_LOCALHOST_ONLY is disabled, falls down to use discovery option.
ASSERT_TRUE(rcutils_set_env("ROS_LOCALHOST_ONLY", "0"));
ASSERT_TRUE(rcutils_set_env("ROS_AUTOMATIC_DISCOVERY_RANGE", "SUBNET"));
ASSERT_TRUE(rcutils_set_env("ROS_STATIC_PEERS", "192.168.0.1;remote.com"));
check_discovery(RMW_AUTOMATIC_DISCOVERY_RANGE_SUBNET, 2);
Expand Down
41 changes: 0 additions & 41 deletions rcl/test/rcl/test_localhost.cpp

This file was deleted.

0 comments on commit 9725f91

Please sign in to comment.