Skip to content
Open
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
1 change: 1 addition & 0 deletions rmw_fastrtps_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ add_library(rmw_fastrtps_cpp
src/rmw_get_gid_for_publisher.cpp
src/rmw_get_implementation_identifier.cpp
src/rmw_get_serialization_format.cpp
src/rmw_get_service_endpoint_info.cpp
src/rmw_get_topic_endpoint_info.cpp
src/rmw_guard_condition.cpp
src/rmw_init.cpp
Expand Down
5 changes: 3 additions & 2 deletions rmw_fastrtps_cpp/src/rmw_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -319,10 +319,11 @@ rmw_create_client(
reader_qos.data_sharing().off();
}

const rosidl_type_hash_t * ser_type_hash = type_supports->get_type_hash_func(type_supports);
if (!get_datareader_qos(
adapted_qos_policies,
*type_supports->response_typesupport->get_type_hash_func(type_supports->response_typesupport),
reader_qos))
reader_qos, ser_type_hash))
{
RMW_SET_ERROR_MSG("create_client() failed setting response DataReader QoS");
return nullptr;
Expand Down Expand Up @@ -389,7 +390,7 @@ rmw_create_client(
if (!get_datawriter_qos(
adapted_qos_policies,
*type_supports->request_typesupport->get_type_hash_func(type_supports->request_typesupport),
writer_qos))
writer_qos, ser_type_hash))
{
RMW_SET_ERROR_MSG("create_client() failed setting request DataWriter QoS");
return nullptr;
Expand Down
46 changes: 46 additions & 0 deletions rmw_fastrtps_cpp/src/rmw_get_service_endpoint_info.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
// Copyright 2025 Minju Lee (이민주). All rights reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "rmw/get_service_endpoint_info.h"
#include "rmw/service_endpoint_info_array.h"
#include "rmw/types.h"
#include "rmw_fastrtps_cpp/identifier.hpp"
#include "rmw_fastrtps_shared_cpp/rmw_common.hpp"

extern "C"
{
rmw_ret_t
rmw_get_clients_info_by_service(
const rmw_node_t * node,
rcutils_allocator_t * allocator,
const char * service_name,
bool no_mangle,
rmw_service_endpoint_info_array_t * clients_info)
{
return rmw_fastrtps_shared_cpp::__rmw_get_clients_info_by_service(
eprosima_fastrtps_identifier, node, allocator, service_name, no_mangle, clients_info);
}

rmw_ret_t
rmw_get_servers_info_by_service(
const rmw_node_t * node,
rcutils_allocator_t * allocator,
const char * service_name,
bool no_mangle,
rmw_service_endpoint_info_array_t * servers_info)
{
return rmw_fastrtps_shared_cpp::__rmw_get_servers_info_by_service(
eprosima_fastrtps_identifier, node, allocator, service_name, no_mangle, servers_info);
}
} // extern "C"
5 changes: 3 additions & 2 deletions rmw_fastrtps_cpp/src/rmw_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -315,10 +315,11 @@ rmw_create_service(
reader_qos.data_sharing().off();
}

const rosidl_type_hash_t * ser_type_hash = type_supports->get_type_hash_func(type_supports);
if (!get_datareader_qos(
adapted_qos_policies,
*type_supports->request_typesupport->get_type_hash_func(type_supports->request_typesupport),
reader_qos))
reader_qos, ser_type_hash))
{
RMW_SET_ERROR_MSG("create_service() failed setting request DataReader QoS");
return nullptr;
Expand Down Expand Up @@ -389,7 +390,7 @@ rmw_create_service(
if (!get_datawriter_qos(
adapted_qos_policies,
*type_supports->response_typesupport->get_type_hash_func(type_supports->response_typesupport),
writer_qos))
writer_qos, ser_type_hash))
{
RMW_SET_ERROR_MSG("create_service() failed setting response DataWriter QoS");
return nullptr;
Expand Down
1 change: 1 addition & 0 deletions rmw_fastrtps_dynamic_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -66,6 +66,7 @@ add_library(rmw_fastrtps_dynamic_cpp
src/rmw_get_gid_for_publisher.cpp
src/rmw_get_implementation_identifier.cpp
src/rmw_get_serialization_format.cpp
src/rmw_get_service_endpoint_info.cpp
src/rmw_get_topic_endpoint_info.cpp
src/rmw_guard_condition.cpp
src/rmw_init.cpp
Expand Down
5 changes: 3 additions & 2 deletions rmw_fastrtps_dynamic_cpp/src/rmw_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -348,10 +348,11 @@ rmw_create_client(
reader_qos.data_sharing().off();
}

const rosidl_type_hash_t * ser_type_hash = type_supports->get_type_hash_func(type_supports);
if (!get_datareader_qos(
adapted_qos_policies,
*type_supports->response_typesupport->get_type_hash_func(type_supports->response_typesupport),
reader_qos))
reader_qos, ser_type_hash))
{
RMW_SET_ERROR_MSG("create_client() failed setting response DataReader QoS");
return nullptr;
Expand Down Expand Up @@ -418,7 +419,7 @@ rmw_create_client(
if (!get_datawriter_qos(
adapted_qos_policies,
*type_supports->request_typesupport->get_type_hash_func(type_supports->request_typesupport),
writer_qos))
writer_qos, ser_type_hash))
{
RMW_SET_ERROR_MSG("create_client() failed setting request DataWriter QoS");
return nullptr;
Expand Down
46 changes: 46 additions & 0 deletions rmw_fastrtps_dynamic_cpp/src/rmw_get_service_endpoint_info.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
// Copyright 2025 Minju Lee (이민주). All rights reserved.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#include "rmw/get_service_endpoint_info.h"
#include "rmw/service_endpoint_info_array.h"
#include "rmw/types.h"
#include "rmw_fastrtps_dynamic_cpp/identifier.hpp"
#include "rmw_fastrtps_shared_cpp/rmw_common.hpp"

extern "C"
{
rmw_ret_t
rmw_get_clients_info_by_service(
const rmw_node_t * node,
rcutils_allocator_t * allocator,
const char * service_name,
bool no_mangle,
rmw_service_endpoint_info_array_t * clients_info)
{
return rmw_fastrtps_shared_cpp::__rmw_get_clients_info_by_service(
eprosima_fastrtps_identifier, node, allocator, service_name, no_mangle, clients_info);
}

rmw_ret_t
rmw_get_servers_info_by_service(
const rmw_node_t * node,
rcutils_allocator_t * allocator,
const char * service_name,
bool no_mangle,
rmw_service_endpoint_info_array_t * servers_info)
{
return rmw_fastrtps_shared_cpp::__rmw_get_servers_info_by_service(
eprosima_fastrtps_identifier, node, allocator, service_name, no_mangle, servers_info);
}
} // extern "C"
5 changes: 3 additions & 2 deletions rmw_fastrtps_dynamic_cpp/src/rmw_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -344,10 +344,11 @@ rmw_create_service(
reader_qos.data_sharing().off();
}

const rosidl_type_hash_t * ser_type_hash = type_supports->get_type_hash_func(type_supports);
if (!get_datareader_qos(
adapted_qos_policies,
*type_supports->request_typesupport->get_type_hash_func(type_supports->request_typesupport),
reader_qos))
reader_qos, ser_type_hash))
{
RMW_SET_ERROR_MSG("create_service() failed setting request DataReader QoS");
return nullptr;
Expand Down Expand Up @@ -418,7 +419,7 @@ rmw_create_service(
if (!get_datawriter_qos(
adapted_qos_policies,
*type_supports->response_typesupport->get_type_hash_func(type_supports->response_typesupport),
writer_qos))
writer_qos, ser_type_hash))
{
RMW_SET_ERROR_MSG("create_service() failed setting response DataWriter QoS");
return nullptr;
Expand Down
1 change: 1 addition & 0 deletions rmw_fastrtps_shared_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -71,6 +71,7 @@ add_library(rmw_fastrtps_shared_cpp
src/rmw_get_endpoint_network_flow.cpp
src/rmw_get_gid_for_client.cpp
src/rmw_get_gid_for_publisher.cpp
src/rmw_get_service_endpoint_info.cpp
src/rmw_get_topic_endpoint_info.cpp
src/rmw_guard_condition.cpp
src/rmw_init.cpp
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -243,7 +243,13 @@ class ParticipantListener : public eprosima::fastdds::dds::DomainParticipantList
// We've handled the error, so clear it out.
rmw_reset_error();
}

rosidl_type_hash_t ser_type_hash;
rosidl_type_hash_t * ser_type_hash_ptr = nullptr;
if (RMW_RET_OK == rmw_dds_common::parse_sertype_hash_from_user_data(
userDataValue.data(), userDataValue.size(), ser_type_hash))
{
ser_type_hash_ptr = &ser_type_hash;
}
context->graph_cache.add_entity(
rmw_fastrtps_shared_cpp::create_rmw_gid(
identifier_,
Expand All @@ -255,7 +261,8 @@ class ParticipantListener : public eprosima::fastdds::dds::DomainParticipantList
identifier_,
proxyData.participant_guid),
qos_profile,
is_reader);
is_reader,
ser_type_hash_ptr);
} else {
context->graph_cache.remove_entity(
rmw_fastrtps_shared_cpp::create_rmw_gid(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,14 +36,16 @@ bool
get_datareader_qos(
const rmw_qos_profile_t & qos_policies,
const rosidl_type_hash_t & type_hash,
eprosima::fastdds::dds::DataReaderQos & reader_qos);
eprosima::fastdds::dds::DataReaderQos & reader_qos,
const rosidl_type_hash_t * ser_type_hash = nullptr);

RMW_FASTRTPS_SHARED_CPP_PUBLIC
bool
get_datawriter_qos(
const rmw_qos_profile_t & qos_policies,
const rosidl_type_hash_t & type_hash,
eprosima::fastdds::dds::DataWriterQos & writer_qos);
eprosima::fastdds::dds::DataWriterQos & writer_qos,
const rosidl_type_hash_t * ser_type_hash = nullptr);

RMW_FASTRTPS_SHARED_CPP_PUBLIC
bool
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@
#include "rmw/event.h"
#include "rmw/features.h"
#include "rmw/rmw.h"
#include "rmw/service_endpoint_info_array.h"
#include "rmw/topic_endpoint_info_array.h"
#include "rmw/types.h"
#include "rmw/names_and_types.h"
Expand Down Expand Up @@ -523,6 +524,26 @@ __rmw_get_subscriptions_info_by_topic(
bool no_mangle,
rmw_topic_endpoint_info_array_t * subscriptions_info);

RMW_FASTRTPS_SHARED_CPP_PUBLIC
rmw_ret_t
__rmw_get_clients_info_by_service(
const char * identifier,
const rmw_node_t * node,
rcutils_allocator_t * allocator,
const char * service_name,
bool no_mangle,
rmw_service_endpoint_info_array_t * clients_info);

RMW_FASTRTPS_SHARED_CPP_PUBLIC
rmw_ret_t
__rmw_get_servers_info_by_service(
const char * identifier,
const rmw_node_t * node,
rcutils_allocator_t * allocator,
const char * service_name,
bool no_mangle,
rmw_service_endpoint_info_array_t * servers_info);

RMW_FASTRTPS_SHARED_CPP_PUBLIC
rmw_ret_t
__rmw_qos_profile_check_compatible(
Expand Down
22 changes: 17 additions & 5 deletions rmw_fastrtps_shared_cpp/src/qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
// limitations under the License.

#include <limits>
#include <string>
#include <vector>

#include "rcutils/logging_macros.h"
Expand Down Expand Up @@ -154,7 +155,8 @@ bool
fill_data_entity_qos_from_profile(
const rmw_qos_profile_t & qos_policies,
const rosidl_type_hash_t & type_hash,
DDSEntityQos & entity_qos)
DDSEntityQos & entity_qos,
const rosidl_type_hash_t * ser_type_hash = nullptr)
{
if (!fill_entity_qos_from_profile(qos_policies, entity_qos)) {
return false;
Expand All @@ -169,6 +171,14 @@ fill_data_entity_qos_from_profile(
// code won't overwrite it.
rmw_reset_error();
}
if (ser_type_hash) {
std::string typehash_str;
if (RMW_RET_OK ==
rmw_dds_common::encode_sertype_hash_for_user_data_qos(*ser_type_hash, typehash_str))
{
user_data_str += typehash_str;
}
}
std::vector<uint8_t> user_data(user_data_str.begin(), user_data_str.end());
entity_qos.user_data().resize(user_data.size());
entity_qos.user_data().setValue(user_data);
Expand All @@ -179,9 +189,10 @@ bool
get_datareader_qos(
const rmw_qos_profile_t & qos_policies,
const rosidl_type_hash_t & type_hash,
eprosima::fastdds::dds::DataReaderQos & datareader_qos)
eprosima::fastdds::dds::DataReaderQos & datareader_qos,
const rosidl_type_hash_t * ser_type_hash)
{
if (fill_data_entity_qos_from_profile(qos_policies, type_hash, datareader_qos)) {
if (fill_data_entity_qos_from_profile(qos_policies, type_hash, datareader_qos, ser_type_hash)) {
// The type support in the RMW implementation is always XCDR1.
constexpr auto rep = eprosima::fastdds::dds::XCDR_DATA_REPRESENTATION;
datareader_qos.representation().clear();
Expand All @@ -196,9 +207,10 @@ bool
get_datawriter_qos(
const rmw_qos_profile_t & qos_policies,
const rosidl_type_hash_t & type_hash,
eprosima::fastdds::dds::DataWriterQos & datawriter_qos)
eprosima::fastdds::dds::DataWriterQos & datawriter_qos,
const rosidl_type_hash_t * ser_type_hash)
{
if (fill_data_entity_qos_from_profile(qos_policies, type_hash, datawriter_qos)) {
if (fill_data_entity_qos_from_profile(qos_policies, type_hash, datawriter_qos, ser_type_hash)) {
// The type support in the RMW implementation is always XCDR1.
constexpr auto rep = eprosima::fastdds::dds::XCDR_DATA_REPRESENTATION;
datawriter_qos.representation().clear();
Expand Down
6 changes: 3 additions & 3 deletions rmw_fastrtps_shared_cpp/src/rmw_count.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -155,8 +155,8 @@ __rmw_count_services(
}
RMW_CHECK_ARGUMENT_FOR_NULL(count, RMW_RET_INVALID_ARGUMENT);
auto common_context = static_cast<rmw_dds_common::Context *>(node->context->impl->common);
const std::string mangled_rp_service_name =
_mangle_topic_name(ros_service_response_prefix, service_name, "Reply").to_string();
return common_context->graph_cache.get_writer_count(mangled_rp_service_name, count);
const std::string mangled_rq_service_name =
_mangle_topic_name(ros_service_requester_prefix, service_name, "Request").to_string();
return common_context->graph_cache.get_reader_count(mangled_rq_service_name, count);
}
} // namespace rmw_fastrtps_shared_cpp
Loading