Skip to content

Commit

Permalink
revert ACL changes and update to match ne namespace changes
Browse files Browse the repository at this point in the history
  • Loading branch information
mikaelarguedas committed Apr 13, 2018
1 parent 75c29e1 commit 24603fa
Show file tree
Hide file tree
Showing 4 changed files with 48 additions and 39 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#include "rmw_fastrtps_cpp/reader_info.hpp"
#include "rmw_fastrtps_cpp/writer_info.hpp"


class ParticipantListener;

typedef struct CustomParticipantInfo
Expand All @@ -43,17 +44,19 @@ typedef struct CustomParticipantInfo
class ParticipantListener : public eprosima::fastrtps::ParticipantListener
{
public:
void onParticipantDiscovery(Participant *, ParticipantDiscoveryInfo info) override
void onParticipantDiscovery(
eprosima::fastrtps::Participant *,
eprosima::fastrtps::ParticipantDiscoveryInfo info) override
{
if (
info.rtps.m_status != DISCOVERED_RTPSPARTICIPANT &&
info.rtps.m_status != REMOVED_RTPSPARTICIPANT &&
info.rtps.m_status != DROPPED_RTPSPARTICIPANT)
info.rtps.m_status != eprosima::fastrtps::rtps::DISCOVERED_RTPSPARTICIPANT &&
info.rtps.m_status != eprosima::fastrtps::rtps::REMOVED_RTPSPARTICIPANT &&
info.rtps.m_status != eprosima::fastrtps::rtps::DROPPED_RTPSPARTICIPANT)
{
return;
}

if (DISCOVERED_RTPSPARTICIPANT == info.rtps.m_status) {
if (eprosima::fastrtps::rtps::DISCOVERED_RTPSPARTICIPANT == info.rtps.m_status) {
// ignore already known GUIDs
if (discovered_names.find(info.rtps.m_guid) == discovered_names.end()) {
auto map = rmw::impl::cpp::parse_key_value(info.rtps.m_userData);
Expand Down Expand Up @@ -90,7 +93,7 @@ class ParticipantListener : public eprosima::fastrtps::ParticipantListener
return names;
}

std::map<GUID_t, std::string> discovered_names;
std::map<eprosima::fastrtps::rtps::GUID_t, std::string> discovered_names;
};

#endif // RMW_FASTRTPS_CPP__CUSTOM_PARTICIPANT_INFO_HPP_
40 changes: 7 additions & 33 deletions rmw_fastrtps_cpp/src/rmw_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,6 @@

#include "rcutils/filesystem.h"
#include "rcutils/logging_macros.h"
#include "rcutils/get_env.h"

#include "rmw/allocators.h"
#include "rmw/error_handling.h"
Expand Down Expand Up @@ -47,8 +46,6 @@
#include "rmw_fastrtps_cpp/identifier.hpp"
#include "rmw_fastrtps_cpp/custom_participant_info.hpp"

#define ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME "ROS_SECURITY_ROOT_DIRECTORY"

using Domain = eprosima::fastrtps::Domain;
using Participant = eprosima::fastrtps::Participant;
using ParticipantAttributes = eprosima::fastrtps::ParticipantAttributes;
Expand Down Expand Up @@ -187,31 +184,16 @@ create_node(

bool
get_security_file_paths(
std::array<std::string, 6> & security_files_paths, const char * node_secure_root)
std::array<std::string, 3> & security_files_paths, const char * node_secure_root)
{
// here assume only 6 files for security
const char * file_names[6] = {
"ca.cert.pem", "cert.pem", "key.pem",
"ca.cert.pem", "governance.p7s", "permissions.p7s"
};
// here assume only 3 files for security
const char * file_names[3] = {"ca.cert.pem", "cert.pem", "key.pem"};
size_t num_files = sizeof(file_names) / sizeof(char *);

std::string file_prefix("file://");

for (size_t i = 0; i < num_files; i++) {
char * file_path;

if (i != 3) {
file_path = rcutils_join_path(node_secure_root, file_names[i]);
} else {
const char * ros_secure_root_env = NULL;
if (rcutils_get_env(ROS_SECURITY_ROOT_DIRECTORY_VAR_NAME, &ros_secure_root_env) == NULL) {
file_path = rcutils_join_path(ros_secure_root_env, file_names[i]);
} else {
return false;
}
}

char * file_path = rcutils_join_path(node_secure_root, file_names[i]);
if (!file_path) {
return false;
}
Expand Down Expand Up @@ -266,7 +248,7 @@ rmw_create_node(
if (security_options->security_root_path) {
// if security_root_path provided, try to find the key and certificate files
#if HAVE_SECURITY
std::array<std::string, 6> security_files_paths;
std::array<std::string, 3> security_files_paths;

if (get_security_file_paths(security_files_paths, security_options->security_root_path)) {
eprosima::fastrtps::rtps::PropertyPolicy property_policy;
Expand All @@ -284,16 +266,8 @@ rmw_create_node(
security_files_paths[2]));
property_policy.properties().emplace_back(
Property("dds.sec.crypto.plugin", "builtin.AES-GCM-GMAC"));

property_policy.properties().emplace_back(Property(
"dds.sec.access.plugin", "builtin.Access-Permissions"));
property_policy.properties().emplace_back(Property(
"dds.sec.access.builtin.Access-Permissions.permissions_ca", security_files_paths[3]));
property_policy.properties().emplace_back(Property(
"dds.sec.access.builtin.Access-Permissions.governance", security_files_paths[4]));
property_policy.properties().emplace_back(Property(
"dds.sec.access.builtin.Access-Permissions.permissions", security_files_paths[5]));

property_policy.properties().emplace_back(
Property("rtps.participant.rtps_protection_kind", "ENCRYPT"));
participantAttrs.rtps.properties = property_policy;
} else if (security_options->enforce_security) {
RMW_SET_ERROR_MSG("couldn't find all security files!");
Expand Down
16 changes: 16 additions & 0 deletions rmw_fastrtps_cpp/src/rmw_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,6 +116,22 @@ rmw_create_publisher(
goto fail;
}

#if HAVE_SECURITY
// see if our participant has a security property set
if (eprosima::fastrtps::rtps::PropertyPolicyHelper::find_property(
participant->getAttributes().rtps.properties,
std::string("dds.sec.crypto.plugin")))
{
// set the encryption property on the publisher
eprosima::fastrtps::rtps::PropertyPolicy publisher_property_policy;
publisher_property_policy.properties().emplace_back(
"rtps.endpoint.submessage_protection_kind", "ENCRYPT");
publisher_property_policy.properties().emplace_back(
"rtps.endpoint.payload_protection_kind", "ENCRYPT");
publisherParam.properties = publisher_property_policy;
}
#endif

// 1 Heartbeat every 10ms
// publisherParam.times.heartbeatPeriod.seconds = 0;
// publisherParam.times.heartbeatPeriod.fraction = 42949673;
Expand Down
16 changes: 16 additions & 0 deletions rmw_fastrtps_cpp/src/rmw_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,22 @@ rmw_create_subscription(
goto fail;
}

#if HAVE_SECURITY
// see if our subscriber has a security property set
if (eprosima::fastrtps::rtps::PropertyPolicyHelper::find_property(
participant->getAttributes().rtps.properties,
std::string("dds.sec.crypto.plugin")))
{
// set the encryption property on the subscriber
eprosima::fastrtps::rtps::PropertyPolicy subscriber_property_policy;
subscriber_property_policy.properties().emplace_back(
"rtps.endpoint.submessage_protection_kind", "ENCRYPT");
subscriber_property_policy.properties().emplace_back(
"rtps.endpoint.payload_protection_kind", "ENCRYPT");
subscriberParam.properties = subscriber_property_policy;
}
#endif

if (!get_datareader_qos(*qos_policies, subscriberParam)) {
RMW_SET_ERROR_MSG("failed to get datareader qos");
goto fail;
Expand Down

0 comments on commit 24603fa

Please sign in to comment.