Skip to content

Commit

Permalink
Support access control (#197)
Browse files Browse the repository at this point in the history
* Refs #2547 eProsima Modifications

Initial changes to correct namespace modifications for pre-cursor to access control list security feature addition.

Refs #2547 eProsima

Modifications to `ROS2` rmw layer that handles `fastrtps`.  Added policy information to cover the addition of the governance and permissions for implementation of an access control list.  At the momemnt the referenced security material might not be correct for the root cert, governance and permission material.

Refs #2547 Update for eProsima's Fast-RTPS ACL

Obtaining the root ca agent is now obtained without a hardcoded path.
- have not accounted for possible need of handling of env string memory for both success and failure.
- above could be a memory leak area.

removing colliding definition, rmw types are defined in rmw itself

remove properties now provided by governance and use sros2 file names

never use using directives in headers

dont use using namespace directive in code. use specific types instead

apply ROS 2 style

* clean rmw_node diff
  • Loading branch information
mikaelarguedas authored May 3, 2018
1 parent a69bab1 commit a9c33de
Show file tree
Hide file tree
Showing 3 changed files with 18 additions and 38 deletions.
24 changes: 18 additions & 6 deletions rmw_fastrtps_cpp/src/rmw_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -184,16 +184,20 @@ create_node(

bool
get_security_file_paths(
std::array<std::string, 3> & security_files_paths, const char * node_secure_root)
std::array<std::string, 6> & security_files_paths, const char * node_secure_root)
{
// here assume only 3 files for security
const char * file_names[3] = {"ca.cert.pem", "cert.pem", "key.pem"};
// 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"
};
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 = rcutils_join_path(node_secure_root, file_names[i]);

if (!file_path) {
return false;
}
Expand Down Expand Up @@ -248,7 +252,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, 3> security_files_paths;
std::array<std::string, 6> security_files_paths;

if (get_security_file_paths(security_files_paths, security_options->security_root_path)) {
eprosima::fastrtps::rtps::PropertyPolicy property_policy;
Expand All @@ -266,8 +270,16 @@ 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("rtps.participant.rtps_protection_kind", "ENCRYPT"));

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]));

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: 0 additions & 16 deletions rmw_fastrtps_cpp/src/rmw_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,22 +116,6 @@ 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: 0 additions & 16 deletions rmw_fastrtps_cpp/src/rmw_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,22 +118,6 @@ 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 a9c33de

Please sign in to comment.