Merge remote-tracking branch 'origin/master' into dds-security

This commit is contained in:
Sid Faber 2020-04-07 19:41:33 +00:00
commit 16134dcaba
3 changed files with 161 additions and 54 deletions

View file

@ -20,9 +20,9 @@ jobs:
# azure ubuntu repo can be flaky so add an alternate source # azure ubuntu repo can be flaky so add an alternate source
run: sed -e 's/azure.archive.ubuntu.com/us.archive.ubuntu.com/g' -e t -e d /etc/apt/sources.list | sudo tee /etc/apt/sources.list.d/nonazure.list run: sed -e 's/azure.archive.ubuntu.com/us.archive.ubuntu.com/g' -e t -e d /etc/apt/sources.list | sudo tee /etc/apt/sources.list.d/nonazure.list
- name: Acquire ROS dependencies - name: Acquire ROS dependencies
uses: ros-tooling/setup-ros@0.0.15 uses: ros-tooling/setup-ros@0.0.17
- name: Build and test ROS - name: Build and test ROS
uses: ros-tooling/action-ros-ci@0.0.14 uses: ros-tooling/action-ros-ci@0.0.15
with: with:
package-name: rmw_cyclonedds_cpp package-name: rmw_cyclonedds_cpp
vcs-repo-file-url: https://raw.githubusercontent.com/ros2/ros2/${{ matrix.rosdistro }}/ros2.repos vcs-repo-file-url: https://raw.githubusercontent.com/ros2/ros2/${{ matrix.rosdistro }}/ros2.repos

View file

@ -10,24 +10,13 @@
<buildtool_depend>ament_cmake_ros</buildtool_depend> <buildtool_depend>ament_cmake_ros</buildtool_depend>
<buildtool_depend>cyclonedds_cmake_module</buildtool_depend> <buildtool_depend>cyclonedds_cmake_module</buildtool_depend>
<buildtool_export_depend>ament_cmake</buildtool_export_depend> <depend>cyclonedds</depend>
<depend>cyclonedds_cmake_module</depend>
<build_depend>cyclonedds</build_depend> <depend>rcutils</depend>
<build_depend>cyclonedds_cmake_module</build_depend> <depend>rmw</depend>
<depend>rosidl_generator_c</depend>
<build_depend>rcutils</build_depend> <depend>rosidl_typesupport_introspection_c</depend>
<build_depend>rmw</build_depend> <depend>rosidl_typesupport_introspection_cpp</depend>
<build_depend>rosidl_generator_c</build_depend>
<build_depend>rosidl_typesupport_introspection_c</build_depend>
<build_depend>rosidl_typesupport_introspection_cpp</build_depend>
<build_export_depend>cyclonedds</build_export_depend>
<build_export_depend>cyclonedds_cmake_module</build_export_depend>
<build_export_depend>rcutils</build_export_depend>
<build_export_depend>rmw</build_export_depend>
<build_export_depend>rosidl_generator_c</build_export_depend>
<build_export_depend>rosidl_typesupport_introspection_c</build_export_depend>
<build_export_depend>rosidl_typesupport_introspection_cpp</build_export_depend>
<test_depend>ament_lint_auto</test_depend> <test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend> <test_depend>ament_lint_common</test_depend>

View file

@ -23,6 +23,7 @@
#include <memory> #include <memory>
#include <vector> #include <vector>
#include <string> #include <string>
#include <tuple>
#include <utility> #include <utility>
#include <regex> #include <regex>
@ -379,6 +380,12 @@ extern "C" rmw_ret_t rmw_init_options_init(
init_options->implementation_identifier = eclipse_cyclonedds_identifier; init_options->implementation_identifier = eclipse_cyclonedds_identifier;
init_options->allocator = allocator; init_options->allocator = allocator;
init_options->impl = nullptr; init_options->impl = nullptr;
#if RMW_VERSION_GTE(0, 8, 2)
init_options->localhost_only = RMW_LOCALHOST_ONLY_DEFAULT;
init_options->domain_id = RMW_DEFAULT_DOMAIN_ID;
init_options->security_context = NULL;
init_options->security_options = rmw_get_zero_initialized_security_options();
#endif
return RMW_RET_OK; return RMW_RET_OK;
} }
@ -395,19 +402,44 @@ extern "C" rmw_ret_t rmw_init_options_copy(const rmw_init_options_t * src, rmw_i
RMW_SET_ERROR_MSG("expected zero-initialized dst"); RMW_SET_ERROR_MSG("expected zero-initialized dst");
return RMW_RET_INVALID_ARGUMENT; return RMW_RET_INVALID_ARGUMENT;
} }
#if RMW_VERSION_GTE(0, 8, 2)
const rcutils_allocator_t * allocator = &src->allocator;
rmw_ret_t ret = RMW_RET_OK;
allocator->deallocate(dst->security_context, allocator->state);
*dst = *src;
dst->security_context = NULL;
dst->security_options = rmw_get_zero_initialized_security_options();
dst->security_context = rcutils_strdup(src->security_context, *allocator);
if (src->security_context && !dst->security_context) {
ret = RMW_RET_BAD_ALLOC;
goto fail;
}
return rmw_security_options_copy(&src->security_options, allocator, &dst->security_options);
fail:
allocator->deallocate(dst->security_context, allocator->state);
return ret;
#else
*dst = *src; *dst = *src;
return RMW_RET_OK; return RMW_RET_OK;
#endif
} }
extern "C" rmw_ret_t rmw_init_options_fini(rmw_init_options_t * init_options) extern "C" rmw_ret_t rmw_init_options_fini(rmw_init_options_t * init_options)
{ {
RMW_CHECK_ARGUMENT_FOR_NULL(init_options, RMW_RET_INVALID_ARGUMENT); RMW_CHECK_ARGUMENT_FOR_NULL(init_options, RMW_RET_INVALID_ARGUMENT);
RCUTILS_CHECK_ALLOCATOR(&init_options->allocator, return RMW_RET_INVALID_ARGUMENT); rcutils_allocator_t & allocator = init_options->allocator;
RCUTILS_CHECK_ALLOCATOR(&allocator, return RMW_RET_INVALID_ARGUMENT);
RMW_CHECK_TYPE_IDENTIFIERS_MATCH( RMW_CHECK_TYPE_IDENTIFIERS_MATCH(
init_options, init_options,
init_options->implementation_identifier, init_options->implementation_identifier,
eclipse_cyclonedds_identifier, eclipse_cyclonedds_identifier,
return RMW_RET_INCORRECT_RMW_IMPLEMENTATION); return RMW_RET_INCORRECT_RMW_IMPLEMENTATION);
#if RMW_VERSION_GTE(0, 8, 2)
allocator.deallocate(init_options->security_context, allocator.state);
rmw_security_options_fini(&init_options->security_options, &allocator);
#endif
*init_options = rmw_get_zero_initialized_init_options(); *init_options = rmw_get_zero_initialized_init_options();
return RMW_RET_OK; return RMW_RET_OK;
} }
@ -426,7 +458,11 @@ extern "C" rmw_ret_t rmw_init(const rmw_init_options_t * options, rmw_context_t
context->instance_id = options->instance_id; context->instance_id = options->instance_id;
context->implementation_identifier = eclipse_cyclonedds_identifier; context->implementation_identifier = eclipse_cyclonedds_identifier;
context->impl = nullptr; context->impl = nullptr;
#if RMW_VERSION_GTE(0, 8, 2)
return rmw_init_options_copy(options, &context->options);
#else
return RMW_RET_OK; return RMW_RET_OK;
#endif
} }
extern "C" rmw_ret_t rmw_node_assert_liveliness(const rmw_node_t * node) extern "C" rmw_ret_t rmw_node_assert_liveliness(const rmw_node_t * node)
@ -657,13 +693,24 @@ static void node_gone_from_domain_locked(dds_domainid_t did)
} }
#endif #endif
static std::string get_node_user_data(const char * node_name, const char * node_namespace) static std::string get_node_user_data_name_ns(const char * node_name, const char * node_namespace)
{ {
return std::string("name=") + std::string(node_name) + return std::string("name=") + std::string(node_name) +
std::string(";namespace=") + std::string(node_namespace) + std::string(";namespace=") + std::string(node_namespace) +
std::string(";"); std::string(";");
} }
#if RMW_VERSION_GTE(0, 8, 2)
static std::string get_node_user_data(
const char * node_name, const char * node_namespace, const char * security_context)
{
return get_node_user_data_name_ns(node_name, node_namespace) +
std::string("securitycontext=") + std::string(security_context) +
std::string(";");
}
#else
#define get_node_user_data get_node_user_data_name_ns
#endif
#if RMW_SUPPORT_SECURITY #if RMW_SUPPORT_SECURITY
/* Returns the full URI of a security file properly formatted for DDS */ /* Returns the full URI of a security file properly formatted for DDS */
bool get_security_file_URI( bool get_security_file_URI(
@ -687,7 +734,11 @@ bool get_security_file_URI(
} }
bool get_security_file_URIs( bool get_security_file_URIs(
#if !RMW_VERSION_GTE(0, 8, 2)
const rmw_node_security_options_t * security_options, const rmw_node_security_options_t * security_options,
#else
const rmw_security_options_t * security_options,
#endif
dds_security_files_t & dds_security_files, rcutils_allocator_t allocator) dds_security_files_t & dds_security_files, rcutils_allocator_t allocator)
{ {
bool ret = false; bool ret = false;
@ -737,7 +788,13 @@ void finalize_security_file_URIs(
/* Attempt to set all the qos properties needed to enable DDS security */ /* Attempt to set all the qos properties needed to enable DDS security */
rmw_ret_t configure_qos_for_security( rmw_ret_t configure_qos_for_security(
dds_qos_t * qos, const rmw_node_security_options_t * security_options) dds_qos_t * qos,
#if !RMW_VERSION_GTE(0, 8, 2)
const rmw_node_security_options_t * security_options
#else
const rmw_security_options_t * security_options
#endif
)
{ {
#if RMW_SUPPORT_SECURITY #if RMW_SUPPORT_SECURITY
rmw_ret_t ret = RMW_RET_UNSUPPORTED; rmw_ret_t ret = RMW_RET_UNSUPPORTED;
@ -779,16 +836,21 @@ rmw_ret_t configure_qos_for_security(
#endif #endif
} }
extern "C" rmw_node_t * rmw_create_node( extern "C" rmw_node_t * rmw_create_node(
rmw_context_t * context, const char * name, rmw_context_t * context, const char * name,
const char * namespace_, size_t domain_id, const char * namespace_, size_t domain_id
const rmw_node_security_options_t * security_options #if !RMW_VERSION_GTE(0, 8, 2)
, const rmw_node_security_options_t * security_options
#endif
#if RMW_VERSION_GTE(0, 8, 1) #if RMW_VERSION_GTE(0, 8, 1)
, bool localhost_only , bool localhost_only
#endif #endif
) )
{ {
#if !RMW_VERSION_GTE(0, 8, 2)
static_cast<void>(context); static_cast<void>(context);
#endif
RET_NULL_X(name, return nullptr); RET_NULL_X(name, return nullptr);
RET_NULL_X(namespace_, return nullptr); RET_NULL_X(namespace_, return nullptr);
#if MULTIDOMAIN #if MULTIDOMAIN
@ -803,9 +865,13 @@ extern "C" rmw_node_t * rmw_create_node(
static_cast<void>(domain_id); static_cast<void>(domain_id);
const dds_domainid_t did = DDS_DOMAIN_DEFAULT; const dds_domainid_t did = DDS_DOMAIN_DEFAULT;
#endif #endif
#if !RMW_VERSION_GTE(0, 8, 2)
RCUTILS_CHECK_ARGUMENT_FOR_NULL(security_options, nullptr); RCUTILS_CHECK_ARGUMENT_FOR_NULL(security_options, nullptr);
#else
rmw_security_options_t * security_options;
RCUTILS_CHECK_ARGUMENT_FOR_NULL(context, nullptr);
security_options = &context->options.security_options;
#endif
rmw_ret_t ret; rmw_ret_t ret;
int dummy_validation_result; int dummy_validation_result;
size_t dummy_invalid_index; size_t dummy_invalid_index;
@ -827,12 +893,11 @@ extern "C" rmw_node_t * rmw_create_node(
#endif #endif
dds_qos_t * qos = dds_create_qos(); dds_qos_t * qos = dds_create_qos();
if (qos == nullptr) { #if RMW_VERSION_GTE(0, 8, 2)
RCUTILS_LOG_ERROR_NAMED("rmw_cyclonedds_cpp", "rmw_create_node: Unable to create qos"); std::string user_data = get_node_user_data(name, namespace_, context->options.security_context);
node_gone_from_domain_locked(did); #else
return nullptr;
}
std::string user_data = get_node_user_data(name, namespace_); std::string user_data = get_node_user_data(name, namespace_);
#endif
dds_qset_userdata(qos, user_data.c_str(), user_data.size()); dds_qset_userdata(qos, user_data.c_str(), user_data.size());
if (configure_qos_for_security(qos, security_options) != RMW_RET_OK) { if (configure_qos_for_security(qos, security_options) != RMW_RET_OK) {
@ -840,9 +905,6 @@ extern "C" rmw_node_t * rmw_create_node(
dds_delete_qos(qos); dds_delete_qos(qos);
node_gone_from_domain_locked(did); node_gone_from_domain_locked(did);
return nullptr; return nullptr;
} else {
RCUTILS_LOG_INFO_NAMED(
"rmw_cyclonedds_cpp", "rmw_create_node: Unable to configure security");
} }
} }
@ -3138,27 +3200,31 @@ static rmw_ret_t do_for_node_user_data(
return do_for_node(node_impl, f); return do_for_node(node_impl, f);
} }
extern "C" rmw_ret_t rmw_get_node_names( extern "C" rmw_ret_t rmw_get_node_names_impl(
const rmw_node_t * node, const rmw_node_t * node,
rcutils_string_array_t * node_names, rcutils_string_array_t * node_names,
rcutils_string_array_t * node_namespaces) rcutils_string_array_t * node_namespaces,
rcutils_string_array_t * security_contexts)
{ {
RET_WRONG_IMPLID(node); RET_WRONG_IMPLID(node);
auto node_impl = static_cast<CddsNode *>(node->data); auto node_impl = static_cast<CddsNode *>(node->data);
if (rmw_check_zero_rmw_string_array(node_names) != RMW_RET_OK || if (RMW_RET_OK != rmw_check_zero_rmw_string_array(node_names) ||
rmw_check_zero_rmw_string_array(node_namespaces) != RMW_RET_OK) RMW_RET_OK != rmw_check_zero_rmw_string_array(node_namespaces))
{ {
return RMW_RET_ERROR; return RMW_RET_ERROR;
} }
std::vector<std::pair<std::string, std::string>> ns; std::regex re {
const auto re = std::regex("^name=(.*);namespace=(.*);$", std::regex::extended); "^name=([^;]*);namespace=([^;]*);(securitycontext=([^;]*);)?",
std::regex_constants::extended
};
std::vector<std::tuple<std::string, std::string, std::string>> ns;
auto oper = auto oper =
[&ns, re](const dds_builtintopic_participant_t & sample, const char * ud) -> bool { [&ns, re](const dds_builtintopic_participant_t & sample, const char * ud) -> bool {
std::cmatch cm; std::cmatch cm;
static_cast<void>(sample); static_cast<void>(sample);
if (std::regex_search(ud, cm, re)) { if (std::regex_search(ud, cm, re)) {
ns.push_back(std::make_pair(std::string(cm[1]), std::string(cm[2]))); ns.push_back(std::make_tuple(std::string(cm[1]), std::string(cm[2]), std::string(cm[4])));
} }
return true; return true;
}; };
@ -3174,17 +3240,31 @@ extern "C" rmw_ret_t rmw_get_node_names(
RMW_SET_ERROR_MSG(rcutils_get_error_string().str); RMW_SET_ERROR_MSG(rcutils_get_error_string().str);
goto fail_alloc; goto fail_alloc;
} }
size_t i; if (security_contexts &&
i = 0; rcutils_string_array_init(security_contexts, ns.size(), &allocator) != RCUTILS_RET_OK)
for (auto && n : ns) { {
node_names->data[i] = rcutils_strdup(n.first.c_str(), allocator); RMW_SET_ERROR_MSG(rcutils_get_error_string().str);
node_namespaces->data[i] = rcutils_strdup(n.second.c_str(), allocator); goto fail_alloc;
}
{
size_t i = 0;
for (auto & n : ns) {
node_names->data[i] = rcutils_strdup(std::get<0>(n).c_str(), allocator);
node_namespaces->data[i] = rcutils_strdup(std::get<1>(n).c_str(), allocator);
if (!node_names->data[i] || !node_namespaces->data[i]) { if (!node_names->data[i] || !node_namespaces->data[i]) {
RMW_SET_ERROR_MSG("rmw_get_node_names for name/namespace"); RMW_SET_ERROR_MSG("rmw_get_node_names for name/namespace");
goto fail_alloc; goto fail_alloc;
} }
if (security_contexts) {
security_contexts->data[i] = rcutils_strdup(std::get<2>(n).c_str(), allocator);
if (!security_contexts->data[i]) {
RMW_SET_ERROR_MSG("rmw_get_node_names for security_context");
goto fail_alloc;
}
}
i++; i++;
} }
}
return RMW_RET_OK; return RMW_RET_OK;
fail_alloc: fail_alloc:
@ -3204,9 +3284,47 @@ fail_alloc:
rcutils_reset_error(); rcutils_reset_error();
} }
} }
if (security_contexts) {
if (rcutils_string_array_fini(security_contexts) != RCUTILS_RET_OK) {
RCUTILS_LOG_ERROR_NAMED(
"rmw_cyclonedds_cpp",
"failed to cleanup during error handling: %s", rcutils_get_error_string().str);
rcutils_reset_error();
}
}
return RMW_RET_BAD_ALLOC; return RMW_RET_BAD_ALLOC;
} }
extern "C" rmw_ret_t rmw_get_node_names(
const rmw_node_t * node,
rcutils_string_array_t * node_names,
rcutils_string_array_t * node_namespaces)
{
return rmw_get_node_names_impl(
node,
node_names,
node_namespaces,
nullptr);
}
#if RMW_VERSION_GTE(0, 8, 2)
extern "C" rmw_ret_t rmw_get_node_names_with_security_contexts(
const rmw_node_t * node,
rcutils_string_array_t * node_names,
rcutils_string_array_t * node_namespaces,
rcutils_string_array_t * security_contexts)
{
if (RMW_RET_OK != rmw_check_zero_rmw_string_array(security_contexts)) {
return RMW_RET_ERROR;
}
return rmw_get_node_names_impl(
node,
node_names,
node_namespaces,
security_contexts);
}
#endif
static rmw_ret_t rmw_collect_data_for_endpoint( static rmw_ret_t rmw_collect_data_for_endpoint(
CddsNode * node_impl, CddsNode * node_impl,
dds_entity_t builtin_topic, dds_entity_t builtin_topic,
@ -3260,7 +3378,7 @@ static void get_node_name(
{ {
static_cast<void>(pp_guid); // only used in assert() static_cast<void>(pp_guid); // only used in assert()
bool node_found = false; bool node_found = false;
const auto re_ud = std::regex("^name=(.*);namespace=(.*);$", std::regex::extended); const auto re_ud = std::regex("^name=([^;]*);namespace=([^;]*);", std::regex::extended);
size_t udsz; size_t udsz;
dds_sample_info_t info; dds_sample_info_t info;
void * msg = NULL; void * msg = NULL;
@ -3512,10 +3630,10 @@ static rmw_ret_t get_node_guids(
const char * node_name, const char * node_namespace, const char * node_name, const char * node_namespace,
std::set<dds_builtintopic_guid_t> & guids) std::set<dds_builtintopic_guid_t> & guids)
{ {
std::string needle = get_node_user_data(node_name, node_namespace); std::string needle = get_node_user_data_name_ns(node_name, node_namespace);
auto oper = auto oper =
[&guids, needle](const dds_builtintopic_participant_t & sample, const char * ud) -> bool { [&guids, needle](const dds_builtintopic_participant_t & sample, const char * ud) -> bool {
if (std::string(ud) == needle) { if (0u == std::string(ud).find(needle)) {
guids.insert(sample.key); guids.insert(sample.key);
} }
return true; /* do keep looking - what if there are many? */ return true; /* do keep looking - what if there are many? */