Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Changes to build against Fast DDS 3.0 #776

Merged
merged 13 commits into from
Jan 22, 2025
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 4 additions & 6 deletions rmw_fastrtps_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,8 @@ find_package(rmw_dds_common REQUIRED)
find_package(rmw_fastrtps_shared_cpp REQUIRED)
find_package(tracetools REQUIRED)

find_package(fastrtps_cmake_module REQUIRED)
clalancette marked this conversation as resolved.
Show resolved Hide resolved
find_package(fastcdr 2 REQUIRED CONFIG)
find_package(fastrtps 2.13 REQUIRED CONFIG)
find_package(FastRTPS 2.13 REQUIRED MODULE)
find_package(fastcdr 2 REQUIRED)
find_package(fastdds 3 REQUIRED)

find_package(rmw REQUIRED)
find_package(rosidl_dynamic_typesupport REQUIRED)
Expand Down Expand Up @@ -100,7 +98,7 @@ add_library(rmw_fastrtps_cpp
)
target_link_libraries(rmw_fastrtps_cpp PUBLIC
fastcdr
fastrtps
fastdds
rmw::rmw
rmw_fastrtps_shared_cpp::rmw_fastrtps_shared_cpp
rosidl_runtime_c::rosidl_runtime_c
Expand Down Expand Up @@ -153,7 +151,7 @@ if(BUILD_TESTING)

ament_add_gtest(test_logging test/test_logging.cpp)
target_link_libraries(test_logging
fastrtps
fastdds
rmw::rmw
rmw_fastrtps_cpp
)
Expand Down
1 change: 0 additions & 1 deletion rmw_fastrtps_cpp/QUALITY_DECLARATION.md
Original file line number Diff line number Diff line change
Expand Up @@ -133,7 +133,6 @@ Results of the nightly linter tests can be found [here](https://ci.ros2.org/view
### Direct Runtime ROS Dependencies [5.i]/[5.ii]

`rmw_fastrtps_cpp` has the following runtime ROS dependencies:
* `fastrtps_cmake_module`: [QUALITY DECLARATION](https://github.com/ros2/rosidl_typesupport_fastrtps/blob/master/fastrtps_cmake_module/QUALITY_DECLARATION.md)
* `rcutils`: [QUALITY DECLARATION](https://github.com/ros2/rcutils/blob/master/QUALITY_DECLARATION.md)
* `rmw`: [QUALITY DECLARATION](https://github.com/ros2/rmw/blob/master/rmw/QUALITY_DECLARATION.md)
* `rmw_dds_common`: [QUALITY DECLARATION](https://github.com/ros2/rmw_dds_common/blob/master/rmw_dds_common/QUALITY_DECLARATION.md)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,9 @@ namespace rmw_fastrtps_cpp
class MessageTypeSupport : public TypeSupport
{
public:
explicit MessageTypeSupport(const message_type_support_callbacks_t * members);
explicit MessageTypeSupport(
const message_type_support_callbacks_t * members,
const rosidl_message_type_support_t * type_supports);
};

} // namespace rmw_fastrtps_cpp
Expand Down
10 changes: 7 additions & 3 deletions rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/ServiceTypeSupport.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,19 +31,23 @@ namespace rmw_fastrtps_cpp
class ServiceTypeSupport : public TypeSupport
{
protected:
ServiceTypeSupport();
explicit ServiceTypeSupport(const rosidl_message_type_support_t * type_supports);
};

class RequestTypeSupport : public ServiceTypeSupport
{
public:
explicit RequestTypeSupport(const service_type_support_callbacks_t * members);
explicit RequestTypeSupport(
const service_type_support_callbacks_t * members,
const rosidl_message_type_support_t * type_supports);
};

class ResponseTypeSupport : public ServiceTypeSupport
{
public:
explicit ResponseTypeSupport(const service_type_support_callbacks_t * members);
explicit ResponseTypeSupport(
const service_type_support_callbacks_t * members,
const rosidl_message_type_support_t * type_supports);
};

} // namespace rmw_fastrtps_cpp
Expand Down
2 changes: 1 addition & 1 deletion rmw_fastrtps_cpp/include/rmw_fastrtps_cpp/TypeSupport.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ class TypeSupport : public rmw_fastrtps_shared_cpp::TypeSupport
bool deserializeROSmessage(
eprosima::fastcdr::Cdr & deser, void * ros_message, const void * impl) const override;

TypeSupport();
explicit TypeSupport(const rosidl_message_type_support_t * type_supports);

protected:
void set_members(const message_type_support_callbacks_t * members);
Expand Down
7 changes: 2 additions & 5 deletions rmw_fastrtps_cpp/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -16,13 +16,11 @@
<author>Ricardo González</author>

<buildtool_depend>ament_cmake_ros</buildtool_depend>
<buildtool_depend>fastrtps_cmake_module</buildtool_depend>

<buildtool_export_depend>ament_cmake</buildtool_export_depend>

<build_depend>fastcdr</build_depend>
<build_depend>fastrtps</build_depend>
<build_depend>fastrtps_cmake_module</build_depend>
<build_depend>fastdds</build_depend>
<build_depend>rcpputils</build_depend>
<build_depend>rcutils</build_depend>
<build_depend>rmw</build_depend>
Expand All @@ -37,8 +35,7 @@
<build_depend>tracetools</build_depend>

<build_export_depend>fastcdr</build_export_depend>
<build_export_depend>fastrtps</build_export_depend>
<build_export_depend>fastrtps_cmake_module</build_export_depend>
<build_export_depend>fastdds</build_export_depend>
<build_export_depend>rcutils</build_export_depend>
<build_export_depend>rmw_dds_common</build_export_depend>
<build_export_depend>rmw_fastrtps_shared_cpp</build_export_depend>
Expand Down
10 changes: 4 additions & 6 deletions rmw_fastrtps_cpp/rmw_fastrtps_cpp-extras.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,9 @@

# copied from rmw_fastrtps_cpp/rmw_fastrtps_cpp-extras.cmake

find_package(fastrtps_cmake_module REQUIRED)
find_package(fastcdr 2 REQUIRED CONFIG)
find_package(fastrtps 2.13 REQUIRED CONFIG)
find_package(FastRTPS 2.13 REQUIRED MODULE)
find_package(fastcdr 2 REQUIRED)
find_package(fastdds 3 REQUIRED)

list(APPEND rmw_fastrtps_cpp_INCLUDE_DIRS ${FastRTPS_INCLUDE_DIR})
list(APPEND rmw_fastrtps_cpp_INCLUDE_DIRS ${FAST_INCLUDE_DIR})
# specific order: dependents before dependencies
list(APPEND rmw_fastrtps_cpp_LIBRARIES fastrtps fastcdr)
list(APPEND rmw_fastrtps_cpp_LIBRARIES fastdds fastcdr)
23 changes: 10 additions & 13 deletions rmw_fastrtps_cpp/src/publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@
#include "fastdds/dds/topic/Topic.hpp"
#include "fastdds/dds/topic/TopicDescription.hpp"
#include "fastdds/dds/topic/qos/TopicQos.hpp"
#include "fastdds/rtps/resources/ResourceManagement.h"
#include "fastdds/rtps/attributes/ResourceManagement.hpp"

#include "rcutils/error_handling.h"
#include "rcutils/macros.h"
Expand Down Expand Up @@ -176,7 +176,7 @@ rmw_fastrtps_cpp::create_publisher(
/////
// Create the Type Support struct
if (!fastdds_type) {
auto tsupport = new (std::nothrow) MessageTypeSupport_cpp(callbacks);
auto tsupport = new (std::nothrow) MessageTypeSupport_cpp(callbacks, type_supports);
if (!tsupport) {
RMW_SET_ERROR_MSG("create_publisher() failed to allocate MessageTypeSupport");
return nullptr;
Expand All @@ -186,18 +186,13 @@ rmw_fastrtps_cpp::create_publisher(
fastdds_type.reset(tsupport);
}

if (ReturnCode_t::RETCODE_OK != fastdds_type.register_type(dds_participant)) {
if (eprosima::fastdds::dds::RETCODE_OK != fastdds_type.register_type(dds_participant)) {
RMW_SET_ERROR_MSG("create_publisher() failed to register type");
return nullptr;
}
info->type_support_ = fastdds_type;

if (!rmw_fastrtps_shared_cpp::register_type_object(type_supports, type_name)) {
RMW_SET_ERROR_MSG_WITH_FORMAT_STRING(
"failed to register type object with incompatible type %s",
type_name.c_str());
return nullptr;
}
info->type_support_->register_type_object_representation();

/////
// Create Listener
Expand Down Expand Up @@ -244,13 +239,13 @@ rmw_fastrtps_cpp::create_publisher(
// Modify specific DataWriter Qos
if (!participant_info->leave_middleware_default_qos) {
if (participant_info->publishing_mode == publishing_mode_t::ASYNCHRONOUS) {
writer_qos.publish_mode().kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
writer_qos.publish_mode().kind = eprosima::fastdds::dds::ASYNCHRONOUS_PUBLISH_MODE;
} else if (participant_info->publishing_mode == publishing_mode_t::SYNCHRONOUS) {
writer_qos.publish_mode().kind = eprosima::fastrtps::SYNCHRONOUS_PUBLISH_MODE;
writer_qos.publish_mode().kind = eprosima::fastdds::dds::SYNCHRONOUS_PUBLISH_MODE;
}

writer_qos.endpoint().history_memory_policy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
eprosima::fastdds::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;

writer_qos.data_sharing().off();
}
Expand Down Expand Up @@ -304,7 +299,9 @@ rmw_fastrtps_cpp::create_publisher(
rmw_publisher_free(rmw_publisher);
});

rmw_publisher->can_loan_messages = info->type_support_->is_plain();
// The type support in the RMW implementation is always XCDR1.
rmw_publisher->can_loan_messages =
info->type_support_->is_plain(eprosima::fastdds::dds::XCDR_DATA_REPRESENTATION);
rmw_publisher->implementation_identifier = eprosima_fastrtps_identifier;
rmw_publisher->data = info;

Expand Down
22 changes: 12 additions & 10 deletions rmw_fastrtps_cpp/src/rmw_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
#include "fastdds/dds/topic/TypeSupport.hpp"
#include "fastdds/dds/topic/qos/TopicQos.hpp"

#include "fastdds/rtps/resources/ResourceManagement.h"
#include "fastdds/rtps/attributes/ResourceManagement.hpp"

#include "rcpputils/scope_exit.hpp"
#include "rcutils/error_handling.h"
Expand Down Expand Up @@ -216,7 +216,8 @@ rmw_create_client(
info->response_type_support_impl_ = response_members;

if (!request_fastdds_type) {
auto tsupport = new (std::nothrow) RequestTypeSupport_cpp(service_members);
auto tsupport = new (std::nothrow) RequestTypeSupport_cpp(service_members,
type_supports->request_typesupport);
if (!tsupport) {
RMW_SET_ERROR_MSG("create_client() failed to allocate request typesupport");
return nullptr;
Expand All @@ -225,7 +226,8 @@ rmw_create_client(
request_fastdds_type.reset(tsupport);
}
if (!response_fastdds_type) {
auto tsupport = new (std::nothrow) ResponseTypeSupport_cpp(service_members);
auto tsupport = new (std::nothrow) ResponseTypeSupport_cpp(service_members,
type_supports->response_typesupport);
if (!tsupport) {
RMW_SET_ERROR_MSG("create_client() failed to allocate response typesupport");
return nullptr;
Expand All @@ -234,13 +236,13 @@ rmw_create_client(
response_fastdds_type.reset(tsupport);
}

if (ReturnCode_t::RETCODE_OK != request_fastdds_type.register_type(dds_participant)) {
if (eprosima::fastdds::dds::RETCODE_OK != request_fastdds_type.register_type(dds_participant)) {
RMW_SET_ERROR_MSG("create_client() failed to register request type");
return nullptr;
}
info->request_type_support_ = request_fastdds_type;

if (ReturnCode_t::RETCODE_OK != response_fastdds_type.register_type(dds_participant)) {
if (eprosima::fastdds::dds::RETCODE_OK != response_fastdds_type.register_type(dds_participant)) {
RMW_SET_ERROR_MSG("create_client() failed to register response type");
return nullptr;
}
Expand Down Expand Up @@ -312,7 +314,7 @@ rmw_create_client(

if (!participant_info->leave_middleware_default_qos) {
reader_qos.endpoint().history_memory_policy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
eprosima::fastdds::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;

reader_qos.data_sharing().off();
}
Expand Down Expand Up @@ -364,13 +366,13 @@ rmw_create_client(
// Modify specific DataWriter Qos
if (!participant_info->leave_middleware_default_qos) {
if (participant_info->publishing_mode == publishing_mode_t::ASYNCHRONOUS) {
writer_qos.publish_mode().kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
writer_qos.publish_mode().kind = eprosima::fastdds::dds::ASYNCHRONOUS_PUBLISH_MODE;
} else if (participant_info->publishing_mode == publishing_mode_t::SYNCHRONOUS) {
writer_qos.publish_mode().kind = eprosima::fastrtps::SYNCHRONOUS_PUBLISH_MODE;
writer_qos.publish_mode().kind = eprosima::fastdds::dds::SYNCHRONOUS_PUBLISH_MODE;
}

writer_qos.endpoint().history_memory_policy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
eprosima::fastdds::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;

writer_qos.data_sharing().off();
}
Expand Down Expand Up @@ -463,7 +465,7 @@ rmw_create_client(
cleanup_info.cancel();
if (TRACETOOLS_TRACEPOINT_ENABLED(rmw_client_init)) {
rmw_gid_t gid{};
rmw_fastrtps_shared_cpp::copy_from_fastrtps_guid_to_byte_array(info->reader_guid_, gid.data);
rmw_fastrtps_shared_cpp::copy_from_fastdds_guid_to_byte_array(info->reader_guid_, gid.data);
TRACETOOLS_DO_TRACEPOINT(rmw_client_init, static_cast<const void *>(rmw_client), gid.data);
}
return rmw_client;
Expand Down
4 changes: 2 additions & 2 deletions rmw_fastrtps_cpp/src/rmw_dynamic_message_type_support.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,13 +76,13 @@ rmw_serialization_support_init(
rosidl_dynamic_typesupport_serialization_support_interface_t methods =
rosidl_dynamic_typesupport_get_zero_initialized_serialization_support_interface();

ret = rosidl_dynamic_typesupport_fastrtps_init_serialization_support_impl(allocator, &impl);
ret = rosidl_dynamic_typesupport_fastdds_init_serialization_support_impl(allocator, &impl);
if (ret != RCUTILS_RET_OK) {
RMW_SET_ERROR_MSG_AND_APPEND_PREV_ERROR("Could not initialize serialization support impl");
goto fail;
}

ret = rosidl_dynamic_typesupport_fastrtps_init_serialization_support_interface(
ret = rosidl_dynamic_typesupport_fastdds_init_serialization_support_interface(
allocator, &methods);
if (ret != RCUTILS_RET_OK) {
RMW_SET_ERROR_MSG_AND_APPEND_PREV_ERROR("could not initialize serialization support interface");
Expand Down
4 changes: 2 additions & 2 deletions rmw_fastrtps_cpp/src/rmw_serialize.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ rmw_serialize(
}

auto callbacks = static_cast<const message_type_support_callbacks_t *>(ts->data);
auto tss = MessageTypeSupport_cpp(callbacks);
auto tss = MessageTypeSupport_cpp(callbacks, type_support);
auto data_length = tss.getEstimatedSerializedSize(ros_message, callbacks);
if (serialized_message->buffer_capacity < data_length) {
if (rmw_serialized_message_resize(serialized_message, data_length) != RMW_RET_OK) {
Expand Down Expand Up @@ -80,7 +80,7 @@ rmw_deserialize(
}

auto callbacks = static_cast<const message_type_support_callbacks_t *>(ts->data);
auto tss = MessageTypeSupport_cpp(callbacks);
auto tss = MessageTypeSupport_cpp(callbacks, type_support);
eprosima::fastcdr::FastBuffer buffer(
reinterpret_cast<char *>(serialized_message->buffer), serialized_message->buffer_length);
eprosima::fastcdr::Cdr deser(buffer, eprosima::fastcdr::Cdr::DEFAULT_ENDIAN);
Expand Down
18 changes: 10 additions & 8 deletions rmw_fastrtps_cpp/src/rmw_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -215,7 +215,8 @@ rmw_create_service(
info->response_type_support_impl_ = response_members;

if (!request_fastdds_type) {
auto tsupport = new (std::nothrow) RequestTypeSupport_cpp(service_members);
auto tsupport = new (std::nothrow) RequestTypeSupport_cpp(service_members,
type_supports->request_typesupport);
if (!tsupport) {
RMW_SET_ERROR_MSG("create_service() failed to allocate request typesupport");
return nullptr;
Expand All @@ -224,7 +225,8 @@ rmw_create_service(
request_fastdds_type.reset(tsupport);
}
if (!response_fastdds_type) {
auto tsupport = new (std::nothrow) ResponseTypeSupport_cpp(service_members);
auto tsupport = new (std::nothrow) ResponseTypeSupport_cpp(service_members,
type_supports->response_typesupport);
if (!tsupport) {
RMW_SET_ERROR_MSG("create_service() failed to allocate response typesupport");
return nullptr;
Expand All @@ -233,13 +235,13 @@ rmw_create_service(
response_fastdds_type.reset(tsupport);
}

if (ReturnCode_t::RETCODE_OK != request_fastdds_type.register_type(dds_participant)) {
if (eprosima::fastdds::dds::RETCODE_OK != request_fastdds_type.register_type(dds_participant)) {
RMW_SET_ERROR_MSG("create_service() failed to register request type");
return nullptr;
}
info->request_type_support_ = request_fastdds_type;

if (ReturnCode_t::RETCODE_OK != response_fastdds_type.register_type(dds_participant)) {
if (eprosima::fastdds::dds::RETCODE_OK != response_fastdds_type.register_type(dds_participant)) {
RMW_SET_ERROR_MSG("create_service() failed to register response type");
return nullptr;
}
Expand Down Expand Up @@ -308,7 +310,7 @@ rmw_create_service(

if (!participant_info->leave_middleware_default_qos) {
reader_qos.endpoint().history_memory_policy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
eprosima::fastdds::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;

reader_qos.data_sharing().off();
}
Expand Down Expand Up @@ -364,13 +366,13 @@ rmw_create_service(
// Modify specific DataWriter Qos
if (!participant_info->leave_middleware_default_qos) {
if (participant_info->publishing_mode == publishing_mode_t::ASYNCHRONOUS) {
writer_qos.publish_mode().kind = eprosima::fastrtps::ASYNCHRONOUS_PUBLISH_MODE;
writer_qos.publish_mode().kind = eprosima::fastdds::dds::ASYNCHRONOUS_PUBLISH_MODE;
} else if (participant_info->publishing_mode == publishing_mode_t::SYNCHRONOUS) {
writer_qos.publish_mode().kind = eprosima::fastrtps::SYNCHRONOUS_PUBLISH_MODE;
writer_qos.publish_mode().kind = eprosima::fastdds::dds::SYNCHRONOUS_PUBLISH_MODE;
}

writer_qos.endpoint().history_memory_policy =
eprosima::fastrtps::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;
eprosima::fastdds::rtps::PREALLOCATED_WITH_REALLOC_MEMORY_MODE;

writer_qos.data_sharing().off();
}
Expand Down
Loading