Skip to content

Commit

Permalink
Merge remote-tracking branch 'github/master' into node_graph_impl
Browse files Browse the repository at this point in the history
* Merge + uncrustify
  • Loading branch information
ross-desmond committed Dec 6, 2018
2 parents 9ea473a + 0c39c9e commit 6bd4fe8
Show file tree
Hide file tree
Showing 21 changed files with 280 additions and 378 deletions.
4 changes: 4 additions & 0 deletions rmw_fastrtps_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,10 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

if(SECURITY)
find_package(OpenSSL REQUIRED)
endif()

find_package(ament_cmake_ros REQUIRED)

find_package(rcutils REQUIRED)
Expand Down
16 changes: 11 additions & 5 deletions rmw_fastrtps_cpp/src/rmw_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,22 +120,28 @@ rmw_create_client(
_register_type(participant, info->response_type_support_);
}

if (!impl->leave_middleware_default_qos) {
subscriberParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
}

subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
subscriberParam.topic.topicDataType = response_type_name;
subscriberParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
if (!qos_policies->avoid_ros_namespace_conventions) {
subscriberParam.topic.topicName = std::string(ros_service_response_prefix) + service_name;
} else {
subscriberParam.topic.topicName = service_name;
}
subscriberParam.topic.topicName += "Reply";

if (!impl->leave_middleware_default_qos) {
publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
publisherParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
}

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;
if (!qos_policies->avoid_ros_namespace_conventions) {
publisherParam.topic.topicName = std::string(ros_service_requester_prefix) + service_name;
} else {
Expand Down
9 changes: 6 additions & 3 deletions rmw_fastrtps_cpp/src/rmw_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,9 +113,12 @@ rmw_create_publisher(
_register_type(participant, info->type_support_);
}

publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
publisherParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
if (!impl->leave_middleware_default_qos) {
publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
publisherParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
}

publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
publisherParam.topic.topicDataType = type_name;
if (!qos_policies->avoid_ros_namespace_conventions) {
Expand Down
16 changes: 11 additions & 5 deletions rmw_fastrtps_cpp/src/rmw_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -132,9 +132,12 @@ rmw_create_service(
_register_type(participant, info->response_type_support_);
}

if (!impl->leave_middleware_default_qos) {
subscriberParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
}

subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
subscriberParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
subscriberParam.topic.topicDataType = request_type_name;
if (!qos_policies->avoid_ros_namespace_conventions) {
subscriberParam.topic.topicName = std::string(ros_service_requester_prefix) + service_name;
Expand All @@ -143,11 +146,14 @@ rmw_create_service(
}
subscriberParam.topic.topicName += "Request";

if (!impl->leave_middleware_default_qos) {
publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
publisherParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
}

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;
if (!qos_policies->avoid_ros_namespace_conventions) {
publisherParam.topic.topicName = std::string(ros_service_response_prefix) + service_name;
} else {
Expand Down
7 changes: 5 additions & 2 deletions rmw_fastrtps_cpp/src/rmw_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -116,8 +116,11 @@ rmw_create_subscription(
_register_type(participant, info->type_support_);
}

subscriberParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
if (!impl->leave_middleware_default_qos) {
subscriberParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
}

subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
subscriberParam.topic.topicDataType = type_name;
if (!qos_policies->avoid_ros_namespace_conventions) {
Expand Down
4 changes: 4 additions & 0 deletions rmw_fastrtps_dynamic_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,10 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

if(SECURITY)
find_package(OpenSSL REQUIRED)
endif()

find_package(ament_cmake_ros REQUIRED)

find_package(rcutils REQUIRED)
Expand Down
16 changes: 11 additions & 5 deletions rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -125,22 +125,28 @@ rmw_create_client(
_register_type(participant, info->response_type_support_);
}

if (!impl->leave_middleware_default_qos) {
subscriberParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
}

subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
subscriberParam.topic.topicDataType = response_type_name;
subscriberParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
if (!qos_policies->avoid_ros_namespace_conventions) {
subscriberParam.topic.topicName = std::string(ros_service_response_prefix) + service_name;
} else {
subscriberParam.topic.topicName = service_name;
}
subscriberParam.topic.topicName += "Reply";

if (!impl->leave_middleware_default_qos) {
publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
publisherParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
}

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;
if (!qos_policies->avoid_ros_namespace_conventions) {
publisherParam.topic.topicName = std::string(ros_service_requester_prefix) + service_name;
} else {
Expand Down
9 changes: 6 additions & 3 deletions rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -108,9 +108,12 @@ rmw_create_publisher(
_register_type(participant, info->type_support_);
}

publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
publisherParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
if (!impl->leave_middleware_default_qos) {
publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
publisherParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
}

publisherParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
publisherParam.topic.topicDataType = type_name;
if (!qos_policies->avoid_ros_namespace_conventions) {
Expand Down
16 changes: 11 additions & 5 deletions rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -137,9 +137,12 @@ rmw_create_service(
_register_type(participant, info->response_type_support_);
}

if (!impl->leave_middleware_default_qos) {
subscriberParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
}

subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
subscriberParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
subscriberParam.topic.topicDataType = request_type_name;
if (!qos_policies->avoid_ros_namespace_conventions) {
subscriberParam.topic.topicName = std::string(ros_service_requester_prefix) + service_name;
Expand All @@ -148,11 +151,14 @@ rmw_create_service(
}
subscriberParam.topic.topicName += "Request";

if (!impl->leave_middleware_default_qos) {
publisherParam.qos.m_publishMode.kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
publisherParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
}

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;
if (!qos_policies->avoid_ros_namespace_conventions) {
publisherParam.topic.topicName = std::string(ros_service_response_prefix) + service_name;
} else {
Expand Down
7 changes: 5 additions & 2 deletions rmw_fastrtps_dynamic_cpp/src/rmw_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -112,8 +112,11 @@ rmw_create_subscription(
_register_type(participant, info->type_support_);
}

subscriberParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
if (!impl->leave_middleware_default_qos) {
subscriberParam.historyMemoryPolicy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
}

subscriberParam.topic.topicKind = eprosima::fastrtps::rtps::NO_KEY;
subscriberParam.topic.topicDataType = type_name;
if (!qos_policies->avoid_ros_namespace_conventions) {
Expand Down
10 changes: 8 additions & 2 deletions rmw_fastrtps_shared_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,10 @@ if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

if(SECURITY)
find_package(OpenSSL REQUIRED)
endif()

find_package(ament_cmake_ros REQUIRED)

find_package(rcutils REQUIRED)
Expand Down Expand Up @@ -63,10 +67,12 @@ add_library(rmw_fastrtps_shared_cpp
src/rmw_trigger_guard_condition.cpp
src/rmw_wait.cpp
src/rmw_wait_set.cpp
src/TypeSupport_impl.cpp)
src/TypeSupport_impl.cpp
)

target_link_libraries(rmw_fastrtps_shared_cpp
fastcdr fastrtps)
fastcdr fastrtps
)

# specific order: dependents before dependencies
ament_target_dependencies(rmw_fastrtps_shared_cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -47,19 +47,29 @@ class TypeSupport : public eprosima::fastrtps::TopicDataType
virtual bool deserializeROSmessage(eprosima::fastcdr::Cdr & deser, void * ros_message) = 0;

RMW_FASTRTPS_SHARED_CPP_PUBLIC
bool serialize(void * data, eprosima::fastrtps::rtps::SerializedPayload_t * payload);
bool getKey(
void * data,
eprosima::fastrtps::rtps::InstanceHandle_t * ihandle,
bool force_md5 = false) override
{
(void)data; (void)ihandle; (void)force_md5;
return false;
}

RMW_FASTRTPS_SHARED_CPP_PUBLIC
bool serialize(void * data, eprosima::fastrtps::rtps::SerializedPayload_t * payload) override;

RMW_FASTRTPS_SHARED_CPP_PUBLIC
bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t * payload, void * data);
bool deserialize(eprosima::fastrtps::rtps::SerializedPayload_t * payload, void * data) override;

RMW_FASTRTPS_SHARED_CPP_PUBLIC
std::function<uint32_t()> getSerializedSizeProvider(void * data);
std::function<uint32_t()> getSerializedSizeProvider(void * data) override;

RMW_FASTRTPS_SHARED_CPP_PUBLIC
void * createData();
void * createData() override;

RMW_FASTRTPS_SHARED_CPP_PUBLIC
void deleteData(void * data);
void deleteData(void * data) override;

RMW_FASTRTPS_SHARED_CPP_PUBLIC
virtual ~TypeSupport() {}
Expand Down
Loading

0 comments on commit 6bd4fe8

Please sign in to comment.