diff --git a/rmw_zenoh_cpp/CMakeLists.txt b/rmw_zenoh_cpp/CMakeLists.txt index f4651c66a..734418f4f 100644 --- a/rmw_zenoh_cpp/CMakeLists.txt +++ b/rmw_zenoh_cpp/CMakeLists.txt @@ -22,10 +22,15 @@ find_package(rcutils REQUIRED) find_package(rosidl_typesupport_fastrtps_c REQUIRED) find_package(rosidl_typesupport_fastrtps_cpp REQUIRED) find_package(rmw REQUIRED) +find_package(rmw_security_common REQUIRED) find_package(rmw_test_fixture REQUIRED) find_package(tracetools REQUIRED) find_package(zenoh_cpp_vendor REQUIRED) +if(SECURITY) + set(HAVE_SECURITY 1) +endif() + add_library(rmw_zenoh_cpp SHARED src/detail/attachment_helpers.cpp src/detail/cdr.cpp @@ -70,6 +75,7 @@ target_link_libraries(rmw_zenoh_cpp rosidl_typesupport_fastrtps_c::rosidl_typesupport_fastrtps_c rosidl_typesupport_fastrtps_cpp::rosidl_typesupport_fastrtps_cpp rmw::rmw + rmw_security_common::rmw_security_common_library tracetools::tracetools zenohcxx::zenohc ) @@ -81,6 +87,7 @@ target_compile_definitions(rmw_zenoh_cpp RMW_VERSION_MAJOR=${rmw_VERSION_MAJOR} RMW_VERSION_MINOR=${rmw_VERSION_MINOR} RMW_VERSION_PATCH=${rmw_VERSION_PATCH} + HAVE_SECURITY=${HAVE_SECURITY} ) add_library(rmw_zenoh_cpp_test_fixture SHARED diff --git a/rmw_zenoh_cpp/package.xml b/rmw_zenoh_cpp/package.xml index 1fb4d971f..f2aac3c52 100644 --- a/rmw_zenoh_cpp/package.xml +++ b/rmw_zenoh_cpp/package.xml @@ -25,6 +25,7 @@ rosidl_typesupport_fastrtps_c rosidl_typesupport_fastrtps_cpp rmw + rmw_security_common rmw_test_fixture tracetools diff --git a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp index 3e3d0b728..2fb58c95e 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp +++ b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.cpp @@ -37,6 +37,7 @@ #include "rcpputils/scope_exit.hpp" #include "rmw/error_handling.h" +#include "rmw_security_common/security.hpp" #include "zenoh_utils.hpp" // Megabytes of SHM to reserve. @@ -52,7 +53,8 @@ class rmw_context_impl_s::Data final : public std::enable_shared_from_this // Constructor. Data( std::size_t domain_id, - const std::string & enclave) + const std::string & enclave, + const rmw_security_options_t & security_options) : domain_id_(std::move(domain_id)), enclave_(std::move(enclave)), is_shutdown_(false), @@ -67,7 +69,55 @@ class rmw_context_impl_s::Data final : public std::enable_shared_from_this if (!config.has_value()) { throw std::runtime_error("Error configuring Zenoh session."); } +#ifdef HAVE_SECURITY + rcutils_allocator_t allocator = rcutils_get_default_allocator(); + rcutils_string_map_t security_files = rcutils_get_zero_initialized_string_map(); + rcutils_ret_t ret = rcutils_string_map_init(&security_files, 0, allocator); + + auto scope_exit = rcpputils::make_scope_exit( + [&security_files]() { + rcutils_ret_t ret = rcutils_string_map_fini(&security_files); + if (ret != RMW_RET_OK) { + throw std::runtime_error("Failed to fini string map for security."); + } + }); + + if (ret != RMW_RET_OK) { + throw std::runtime_error("Failed to initialize string map for security."); + } + if (get_security_files_support_pkcs( + false, "", security_options.security_root_path, &security_files) == RMW_RET_OK) + { + config.value().insert_json5("connect/endpoints", "[\"tls/localhost:7447\"]"); + config.value().insert_json5("listen/endpoints", "[\"tls/localhost:0\"]"); + + std::string tls_config = "{\"link\": \n" + "\t\t{ \n" + "\t\t\t\"protocols\": [ \n" + "\t\t\t\t\"tls\" \n" + "\t\t\t], \n" + "\t\t\t\"tls\": { \n" + "\t\t\t\t\"enable_mtls\": true, \n" + "\t\t\t\t\"verify_name_on_connect\": false, \n" + "\t\t\t\t\"root_ca_certificate\": \"" + std::string(rcutils_string_map_get(&security_files, + "IDENTITY_CA")) + "\",\n" + + "\t\t\t\t\"listen_private_key\": \"" + std::string(rcutils_string_map_get(&security_files, + "PRIVATE_KEY")) + "\",\n" + + "\t\t\t\t\"listen_certificate\": \"" + std::string(rcutils_string_map_get(&security_files, + "CERTIFICATE")) + "\",\n" + + "\t\t\t\t\"connect_private_key\": \"" + std::string(rcutils_string_map_get(&security_files, + "PRIVATE_KEY")) + "\",\n" + + "\t\t\t\t\"connect_certificate\": \"" + std::string(rcutils_string_map_get(&security_files, + "CERTIFICATE")) + "\",\n" + + "\t\t\t}, \n" + "\t\t}, \n" + "\t}\n"; + config.value().insert_json5( + "transport", + tls_config); + } +#endif zenoh::ZResult result; #ifndef _MSC_VER @@ -100,8 +150,8 @@ class rmw_context_impl_s::Data final : public std::enable_shared_from_this constexpr int64_t ticks_between_print(std::chrono::milliseconds(1000) / sleep_time); do { zenoh::ZResult result; - const auto zids = this->session_->get_routers_z_id(&result); - if (result == Z_OK && !zids.empty()) { + this->session_->get_routers_z_id(&result); + if (result == Z_OK) { break; } if ((connection_attempts % ticks_between_print) == 0) { @@ -441,9 +491,10 @@ class rmw_context_impl_s::Data final : public std::enable_shared_from_this ///============================================================================= rmw_context_impl_s::rmw_context_impl_s( const std::size_t domain_id, - const std::string & enclave) + const std::string & enclave, + const rmw_security_options_t & security_options) { - data_ = std::make_shared(domain_id, std::move(enclave)); + data_ = std::make_shared(domain_id, std::move(enclave), security_options); data_->init(); } diff --git a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.hpp b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.hpp index a2fdaf5e8..044c4092b 100644 --- a/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.hpp +++ b/rmw_zenoh_cpp/src/detail/rmw_context_impl_s.hpp @@ -40,7 +40,8 @@ struct rmw_context_impl_s final // check has not succeeded. rmw_context_impl_s( const std::size_t domain_id, - const std::string & enclave); + const std::string & enclave, + const rmw_security_options_t & security_options); ~rmw_context_impl_s(); diff --git a/rmw_zenoh_cpp/src/rmw_init.cpp b/rmw_zenoh_cpp/src/rmw_init.cpp index cb34697c9..947e542e3 100644 --- a/rmw_zenoh_cpp/src/rmw_init.cpp +++ b/rmw_zenoh_cpp/src/rmw_init.cpp @@ -110,7 +110,8 @@ rmw_init(const rmw_init_options_t * options, rmw_context_t * context) return RMW_RET_BAD_ALLOC, rmw_context_impl_t, context->actual_domain_id, - std::string(options->enclave) + std::string(options->enclave), + context->options.security_options ); free_options.cancel();