diff --git a/rmw_zenoh_cpp/CMakeLists.txt b/rmw_zenoh_cpp/CMakeLists.txt
index 732cd470..6f8e6581 100644
--- a/rmw_zenoh_cpp/CMakeLists.txt
+++ b/rmw_zenoh_cpp/CMakeLists.txt
@@ -21,9 +21,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_dds_common REQUIRED)
find_package(tracetools REQUIRED)
find_package(zenoh_cpp_vendor REQUIRED)
+if(SECURITY)
+ find_package(OpenSSL REQUIRED)
+ set(HAVE_SECURITY 1)
+endif()
+
add_library(rmw_zenoh_cpp SHARED
src/detail/attachment_helpers.cpp
src/detail/cdr.cpp
@@ -68,6 +74,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_dds_common::rmw_dds_common_library
tracetools::tracetools
zenohcxx::zenohc
)
@@ -79,6 +86,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}
)
ament_export_targets(export_rmw_zenoh_cpp)
diff --git a/rmw_zenoh_cpp/package.xml b/rmw_zenoh_cpp/package.xml
index e8b4288a..997391ad 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_dds_common
tracetools
ament_lint_auto
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 e6198f3a..5055097c 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_dds_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,37 @@ 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
+ std::unordered_map security_files_paths;
+ if (rmw_dds_common::get_security_files(
+ true, "", security_options->security_root_path, security_files_paths))
+ {
+ 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\": \"" + security_files_paths["IDENTITY_CA"] + "\",\n" +
+ "\t\t\t\t\"listen_private_key\": \"" + security_files_paths["PRIVATE_KEY"] + "\",\n" +
+ "\t\t\t\t\"listen_certificate\": \"" + security_files_paths["CERTIFICATE"] + "\",\n" +
+ "\t\t\t\t\"connect_private_key\": \"" + security_files_paths["PRIVATE_KEY"] + "\",\n" +
+ "\t\t\t\t\"connect_certificate\": \"" + security_files_paths["CERTIFICATE"] + "\",\n" +
+ "\t\t\t}, \n"
+ "\t\t}, \n"
+ "\t}\n";
+ config.value().insert_json5(
+ "transport",
+ tls_config);
+ } else {
+ std::cout << "Error getting secutiry data" << std::endl;
+ }
+#endif
zenoh::ZResult result;
#ifndef _MSC_VER
@@ -432,9 +464,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 a2fdaf5e..310c3352 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 cb34697c..647c5066 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();