Skip to content

Commit

Permalink
apply ROS 2 style
Browse files Browse the repository at this point in the history
  • Loading branch information
mikaelarguedas committed Apr 13, 2018
1 parent f1ed133 commit 75c29e1
Show file tree
Hide file tree
Showing 6 changed files with 34 additions and 29 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -756,7 +756,9 @@ bool TypeSupport<MembersType>::serialize(
}

template<typename MembersType>
bool TypeSupport<MembersType>::deserialize(eprosima::fastrtps::rtps::SerializedPayload_t * payload, void * data)
bool TypeSupport<MembersType>::deserialize(
eprosima::fastrtps::rtps::SerializedPayload_t * payload,
void * data)
{
assert(data);
assert(payload);
Expand Down
6 changes: 4 additions & 2 deletions rmw_fastrtps_cpp/src/rmw_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,8 @@ rmw_create_client(

subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
subscriberParam.topic.topicDataType = response_type_name;
subscriberParam.historyMemoryPolicy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
subscriberParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
rcutils_ret_t ret = _assign_partitions_to_attributes(
service_name, ros_service_response_prefix,
qos_policies->avoid_ros_namespace_conventions, &subscriberParam);
Expand All @@ -140,7 +141,8 @@ rmw_create_client(
publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
publisherParam.topic.topicDataType = request_type_name;
publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
publisherParam.historyMemoryPolicy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
publisherParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
ret = _assign_partitions_to_attributes(
service_name, ros_service_requester_prefix,
qos_policies->avoid_ros_namespace_conventions, &publisherParam);
Expand Down
35 changes: 15 additions & 20 deletions rmw_fastrtps_cpp/src/rmw_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -190,23 +190,24 @@ get_security_file_paths(
std::array<std::string, 6> & 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"};
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;

if (i != 3) {
file_path = rcutils_join_path(node_secure_root, file_names[i]);
}
else {
} 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 {
} else {
return false;
}
}
Expand Down Expand Up @@ -268,16 +269,6 @@ rmw_create_node(
std::array<std::string, 6> security_files_paths;

if (get_security_file_paths(security_files_paths, security_options->security_root_path)) {
#if DEBUG
fprintf(stdout, "%s\n%s\n%s\n%s\n%s\n%s\n", \
security_files_paths[0].c_str(), \
security_files_paths[1].c_str(), \
security_files_paths[2].c_str(), \
security_files_paths[3].c_str(), \
security_files_paths[4].c_str(), \
security_files_paths[5].c_str());
#endif

eprosima::fastrtps::rtps::PropertyPolicy property_policy;
using Property = eprosima::fastrtps::rtps::Property;
property_policy.properties().emplace_back(
Expand All @@ -294,10 +285,14 @@ rmw_create_node(
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(
"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) {
Expand Down
6 changes: 4 additions & 2 deletions rmw_fastrtps_cpp/src/rmw_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,11 +104,13 @@ rmw_create_publisher(
}

publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
publisherParam.historyMemoryPolicy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
publisherParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
publisherParam.topic.topicDataType = type_name;
rcutils_ret_t ret = _assign_partitions_to_attributes(
topic_name, ros_topic_prefix, qos_policies->avoid_ros_namespace_conventions, &publisherParam);
topic_name, ros_topic_prefix,
qos_policies->avoid_ros_namespace_conventions, &publisherParam);
if (ret != RCUTILS_RET_OK) {
// error msg already set
goto fail;
Expand Down
6 changes: 4 additions & 2 deletions rmw_fastrtps_cpp/src/rmw_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,8 @@ rmw_create_service(
}

subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
subscriberParam.historyMemoryPolicy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
subscriberParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
subscriberParam.topic.topicDataType = request_type_name;
rcutils_ret_t ret = _assign_partitions_to_attributes(
service_name, ros_service_requester_prefix,
Expand All @@ -150,7 +151,8 @@ rmw_create_service(
publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
publisherParam.topic.topicDataType = response_type_name;
publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
publisherParam.historyMemoryPolicy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
publisherParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
ret = _assign_partitions_to_attributes(
service_name, ros_service_response_prefix,
qos_policies->avoid_ros_namespace_conventions, &publisherParam);
Expand Down
6 changes: 4 additions & 2 deletions rmw_fastrtps_cpp/src/rmw_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,11 +106,13 @@ rmw_create_subscription(
_register_type(participant, info->type_support_, info->typesupport_identifier_);
}

subscriberParam.historyMemoryPolicy = eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
subscriberParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
subscriberParam.topic.topicDataType = type_name;
rcutils_ret_t ret = _assign_partitions_to_attributes(
topic_name, ros_topic_prefix, qos_policies->avoid_ros_namespace_conventions, &subscriberParam);
topic_name, ros_topic_prefix,
qos_policies->avoid_ros_namespace_conventions, &subscriberParam);
if (ret != RCUTILS_RET_OK) {
// error msg already set
goto fail;
Expand Down

0 comments on commit 75c29e1

Please sign in to comment.