Skip to content
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
17 changes: 11 additions & 6 deletions rmw_fastrtps_cpp/src/rmw_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,8 @@
#include "rmw/rmw.h"
#include "rmw/validate_full_topic_name.h"

#include "rmw_dds_common/qos.hpp"

#include "rmw_fastrtps_shared_cpp/custom_client_info.hpp"
#include "rmw_fastrtps_shared_cpp/custom_participant_info.hpp"
#include "rmw_fastrtps_shared_cpp/names.hpp"
Expand Down Expand Up @@ -88,9 +90,12 @@ rmw_create_client(
}
}

rmw_qos_profile_t adapted_qos_policies =
rmw_dds_common::qos_profile_update_best_available_for_services(*qos_policies);

/////
// Check RMW QoS
if (!is_valid_qos(*qos_policies)) {
if (!is_valid_qos(adapted_qos_policies)) {
RMW_SET_ERROR_MSG("create_client() called with invalid QoS");
return nullptr;
}
Expand Down Expand Up @@ -143,9 +148,9 @@ rmw_create_client(
std::string response_type_name = _create_type_name(response_members);

std::string request_topic_name = _create_topic_name(
qos_policies, ros_service_requester_prefix, service_name, "Request").to_string();
&adapted_qos_policies, ros_service_requester_prefix, service_name, "Request").to_string();
std::string response_topic_name = _create_topic_name(
qos_policies, ros_service_response_prefix, service_name, "Reply").to_string();
&adapted_qos_policies, ros_service_response_prefix, service_name, "Reply").to_string();

// Get request topic and type
eprosima::fastdds::dds::TypeSupport request_fastdds_type;
Expand Down Expand Up @@ -258,7 +263,7 @@ rmw_create_client(
// Create and register Topics
// Same default topic QoS for both topics
eprosima::fastdds::dds::TopicQos topic_qos = dds_participant->get_default_topic_qos();
if (!get_topic_qos(*qos_policies, topic_qos)) {
if (!get_topic_qos(adapted_qos_policies, topic_qos)) {
RMW_SET_ERROR_MSG("create_client() failed setting topic QoS");
return nullptr;
}
Expand Down Expand Up @@ -315,7 +320,7 @@ rmw_create_client(
reader_qos.data_sharing().off();
}

if (!get_datareader_qos(*qos_policies, reader_qos)) {
if (!get_datareader_qos(adapted_qos_policies, reader_qos)) {
RMW_SET_ERROR_MSG("create_client() failed setting response DataReader QoS");
return nullptr;
}
Expand Down Expand Up @@ -365,7 +370,7 @@ rmw_create_client(
writer_qos.data_sharing().off();
}

if (!get_datawriter_qos(*qos_policies, writer_qos)) {
if (!get_datawriter_qos(adapted_qos_policies, writer_qos)) {
RMW_SET_ERROR_MSG("create_client() failed setting request DataWriter QoS");
return nullptr;
}
Expand Down
15 changes: 14 additions & 1 deletion rmw_fastrtps_cpp/src/rmw_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,10 +17,13 @@

#include "rmw/allocators.h"
#include "rmw/error_handling.h"
#include "rmw/get_topic_endpoint_info.h"
#include "rmw/rmw.h"

#include "rmw/impl/cpp/macros.hpp"

#include "rmw_dds_common/qos.hpp"

#include "rmw_fastrtps_shared_cpp/custom_participant_info.hpp"
#include "rmw_fastrtps_shared_cpp/custom_publisher_info.hpp"
#include "rmw_fastrtps_shared_cpp/publisher.hpp"
Expand Down Expand Up @@ -72,6 +75,16 @@ rmw_create_publisher(
node->implementation_identifier,
eprosima_fastrtps_identifier,
return nullptr);
RMW_CHECK_ARGUMENT_FOR_NULL(qos_policies, nullptr);

// Adapt any 'best available' QoS options
rmw_qos_profile_t adapted_qos_policies = *qos_policies;
rmw_ret_t ret = rmw_dds_common::qos_profile_get_best_available_for_topic_publisher(
node, topic_name, &adapted_qos_policies, rmw_get_subscriptions_info_by_topic);
if (RMW_RET_OK != ret) {
return nullptr;
}


auto participant_info =
static_cast<CustomParticipantInfo *>(node->context->impl->participant_info);
Expand All @@ -80,7 +93,7 @@ rmw_create_publisher(
participant_info,
type_supports,
topic_name,
qos_policies,
&adapted_qos_policies,
publisher_options,
false,
true);
Expand Down
17 changes: 11 additions & 6 deletions rmw_fastrtps_cpp/src/rmw_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@
#include "rmw/rmw.h"
#include "rmw/validate_full_topic_name.h"

#include "rmw_dds_common/qos.hpp"

#include "rmw_fastrtps_shared_cpp/custom_participant_info.hpp"
#include "rmw_fastrtps_shared_cpp/custom_service_info.hpp"
#include "rmw_fastrtps_shared_cpp/names.hpp"
Expand Down Expand Up @@ -93,9 +95,12 @@ rmw_create_service(
}
}

rmw_qos_profile_t adapted_qos_policies =
rmw_dds_common::qos_profile_update_best_available_for_services(*qos_policies);

/////
// Check RMW QoS
if (!is_valid_qos(*qos_policies)) {
if (!is_valid_qos(adapted_qos_policies)) {
RMW_SET_ERROR_MSG("create_service() called with invalid QoS");
return nullptr;
}
Expand Down Expand Up @@ -148,9 +153,9 @@ rmw_create_service(
std::string response_type_name = _create_type_name(response_members);

std::string request_topic_name = _create_topic_name(
qos_policies, ros_service_requester_prefix, service_name, "Request").to_string();
&adapted_qos_policies, ros_service_requester_prefix, service_name, "Request").to_string();
std::string response_topic_name = _create_topic_name(
qos_policies, ros_service_response_prefix, service_name, "Reply").to_string();
&adapted_qos_policies, ros_service_response_prefix, service_name, "Reply").to_string();

// Get request topic and type
eprosima::fastdds::dds::TypeSupport request_fastdds_type;
Expand Down Expand Up @@ -260,7 +265,7 @@ rmw_create_service(
// Create and register Topics
// Same default topic QoS for both topics
eprosima::fastdds::dds::TopicQos topic_qos = dds_participant->get_default_topic_qos();
if (!get_topic_qos(*qos_policies, topic_qos)) {
if (!get_topic_qos(adapted_qos_policies, topic_qos)) {
RMW_SET_ERROR_MSG("create_service() failed setting topic QoS");
return nullptr;
}
Expand Down Expand Up @@ -314,7 +319,7 @@ rmw_create_service(
reader_qos.data_sharing().off();
}

if (!get_datareader_qos(*qos_policies, reader_qos)) {
if (!get_datareader_qos(adapted_qos_policies, reader_qos)) {
RMW_SET_ERROR_MSG("create_service() failed setting request DataReader QoS");
return nullptr;
}
Expand Down Expand Up @@ -368,7 +373,7 @@ rmw_create_service(
writer_qos.data_sharing().off();
}

if (!get_datawriter_qos(*qos_policies, writer_qos)) {
if (!get_datawriter_qos(adapted_qos_policies, writer_qos)) {
RMW_SET_ERROR_MSG("create_service() failed setting response DataWriter QoS");
return nullptr;
}
Expand Down
14 changes: 13 additions & 1 deletion rmw_fastrtps_cpp/src/rmw_subscription.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,8 +18,11 @@

#include "rmw/allocators.h"
#include "rmw/error_handling.h"
#include "rmw/get_topic_endpoint_info.h"
#include "rmw/rmw.h"

#include "rmw_dds_common/qos.hpp"

#include "rmw_fastrtps_shared_cpp/custom_participant_info.hpp"
#include "rmw_fastrtps_shared_cpp/custom_subscriber_info.hpp"
#include "rmw_fastrtps_shared_cpp/rmw_common.hpp"
Expand Down Expand Up @@ -68,14 +71,23 @@ rmw_create_subscription(
node->implementation_identifier,
eprosima_fastrtps_identifier,
return nullptr);
RMW_CHECK_ARGUMENT_FOR_NULL(qos_policies, nullptr);

// Adapt any 'best available' QoS options
rmw_qos_profile_t adapted_qos_policies = *qos_policies;
rmw_ret_t ret = rmw_dds_common::qos_profile_get_best_available_for_topic_subscription(
node, topic_name, &adapted_qos_policies, rmw_get_publishers_info_by_topic);
if (RMW_RET_OK != ret) {
return nullptr;
}

auto participant_info =
static_cast<CustomParticipantInfo *>(node->context->impl->participant_info);
rmw_subscription_t * subscription = rmw_fastrtps_cpp::create_subscription(
participant_info,
type_supports,
topic_name,
qos_policies,
&adapted_qos_policies,
subscription_options,
false, // use no keyed topic
true); // create subscription listener
Expand Down
17 changes: 11 additions & 6 deletions rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,8 @@
#include "rmw/rmw.h"
#include "rmw/validate_full_topic_name.h"

#include "rmw_dds_common/qos.hpp"

#include "rosidl_typesupport_introspection_cpp/identifier.hpp"

#include "rosidl_typesupport_introspection_c/identifier.h"
Expand Down Expand Up @@ -91,9 +93,12 @@ rmw_create_client(
}
}

rmw_qos_profile_t adapted_qos_policies =
rmw_dds_common::qos_profile_update_best_available_for_services(*qos_policies);

/////
// Check RMW QoS
if (!is_valid_qos(*qos_policies)) {
if (!is_valid_qos(adapted_qos_policies)) {
RMW_SET_ERROR_MSG("create_client() called with invalid QoS");
return nullptr;
}
Expand Down Expand Up @@ -150,9 +155,9 @@ rmw_create_client(
untyped_response_members, type_support->typesupport_identifier);

std::string response_topic_name = _create_topic_name(
qos_policies, ros_service_response_prefix, service_name, "Reply").to_string();
&adapted_qos_policies, ros_service_response_prefix, service_name, "Reply").to_string();
std::string request_topic_name = _create_topic_name(
qos_policies, ros_service_requester_prefix, service_name, "Request").to_string();
&adapted_qos_policies, ros_service_requester_prefix, service_name, "Request").to_string();

// Get request topic and type
eprosima::fastdds::dds::TypeSupport request_fastdds_type;
Expand Down Expand Up @@ -289,7 +294,7 @@ rmw_create_client(
// Create and register Topics
// Same default topic QoS for both topics
eprosima::fastdds::dds::TopicQos topic_qos = dds_participant->get_default_topic_qos();
if (!get_topic_qos(*qos_policies, topic_qos)) {
if (!get_topic_qos(adapted_qos_policies, topic_qos)) {
RMW_SET_ERROR_MSG("create_client() failed setting topic QoS");
return nullptr;
}
Expand Down Expand Up @@ -346,7 +351,7 @@ rmw_create_client(
reader_qos.data_sharing().off();
}

if (!get_datareader_qos(*qos_policies, reader_qos)) {
if (!get_datareader_qos(adapted_qos_policies, reader_qos)) {
RMW_SET_ERROR_MSG("create_client() failed setting response DataReader QoS");
return nullptr;
}
Expand Down Expand Up @@ -396,7 +401,7 @@ rmw_create_client(
writer_qos.data_sharing().off();
}

if (!get_datawriter_qos(*qos_policies, writer_qos)) {
if (!get_datawriter_qos(adapted_qos_policies, writer_qos)) {
RMW_SET_ERROR_MSG("create_client() failed setting request DataWriter QoS");
return nullptr;
}
Expand Down
14 changes: 13 additions & 1 deletion rmw_fastrtps_dynamic_cpp/src/rmw_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,10 +16,13 @@

#include "rmw/allocators.h"
#include "rmw/error_handling.h"
#include "rmw/get_topic_endpoint_info.h"
#include "rmw/rmw.h"

#include "rmw/impl/cpp/macros.hpp"

#include "rmw_dds_common/qos.hpp"

#include "rmw_fastrtps_shared_cpp/custom_participant_info.hpp"
#include "rmw_fastrtps_shared_cpp/custom_publisher_info.hpp"
#include "rmw_fastrtps_shared_cpp/publisher.hpp"
Expand Down Expand Up @@ -74,14 +77,23 @@ rmw_create_publisher(
node->implementation_identifier,
eprosima_fastrtps_identifier,
return nullptr);
RMW_CHECK_ARGUMENT_FOR_NULL(qos_policies, nullptr);

// Adapt any 'best available' QoS options
rmw_qos_profile_t adapted_qos_policies = *qos_policies;
rmw_ret_t ret = rmw_dds_common::qos_profile_get_best_available_for_topic_publisher(
node, topic_name, &adapted_qos_policies, rmw_get_subscriptions_info_by_topic);
if (RMW_RET_OK != ret) {
return nullptr;
}

auto participant_info =
static_cast<CustomParticipantInfo *>(node->context->impl->participant_info);
rmw_publisher_t * publisher = rmw_fastrtps_dynamic_cpp::create_publisher(
participant_info,
type_supports,
topic_name,
qos_policies,
&adapted_qos_policies,
publisher_options,
false,
true);
Expand Down
17 changes: 11 additions & 6 deletions rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,8 @@
#include "rmw/rmw.h"
#include "rmw/validate_full_topic_name.h"

#include "rmw_dds_common/qos.hpp"

#include "rmw_fastrtps_shared_cpp/rmw_common.hpp"

#include "rosidl_typesupport_introspection_cpp/identifier.hpp"
Expand Down Expand Up @@ -99,9 +101,12 @@ rmw_create_service(
}
}

rmw_qos_profile_t adapted_qos_policies =
rmw_dds_common::qos_profile_update_best_available_for_services(*qos_policies);

/////
// Check RMW QoS
if (!is_valid_qos(*qos_policies)) {
if (!is_valid_qos(adapted_qos_policies)) {
RMW_SET_ERROR_MSG("create_service() called with invalid QoS");
return nullptr;
}
Expand Down Expand Up @@ -155,9 +160,9 @@ rmw_create_service(
untyped_response_members, type_support->typesupport_identifier);

std::string response_topic_name = _create_topic_name(
qos_policies, ros_service_response_prefix, service_name, "Reply").to_string();
&adapted_qos_policies, ros_service_response_prefix, service_name, "Reply").to_string();
std::string request_topic_name = _create_topic_name(
qos_policies, ros_service_requester_prefix, service_name, "Request").to_string();
&adapted_qos_policies, ros_service_requester_prefix, service_name, "Request").to_string();

// Get request topic and type
eprosima::fastdds::dds::TypeSupport request_fastdds_type;
Expand Down Expand Up @@ -291,7 +296,7 @@ rmw_create_service(
// Create and register Topics
// Same default topic QoS for both topics
eprosima::fastdds::dds::TopicQos topic_qos = dds_participant->get_default_topic_qos();
if (!get_topic_qos(*qos_policies, topic_qos)) {
if (!get_topic_qos(adapted_qos_policies, topic_qos)) {
RMW_SET_ERROR_MSG("create_service() failed setting topic QoS");
return nullptr;
}
Expand Down Expand Up @@ -345,7 +350,7 @@ rmw_create_service(
reader_qos.data_sharing().off();
}

if (!get_datareader_qos(*qos_policies, reader_qos)) {
if (!get_datareader_qos(adapted_qos_policies, reader_qos)) {
RMW_SET_ERROR_MSG("create_service() failed setting request DataReader QoS");
return nullptr;
}
Expand Down Expand Up @@ -399,7 +404,7 @@ rmw_create_service(
writer_qos.data_sharing().off();
}

if (!get_datawriter_qos(*qos_policies, writer_qos)) {
if (!get_datawriter_qos(adapted_qos_policies, writer_qos)) {
RMW_SET_ERROR_MSG("create_service() failed setting response DataWriter QoS");
return nullptr;
}
Expand Down
Loading