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
11 changes: 7 additions & 4 deletions rmw_dds_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ find_package(rcpputils REQUIRED)
find_package(rcutils REQUIRED)
find_package(rmw REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(rosidl_runtime_c REQUIRED)

ament_add_default_options()
ament_export_dependencies(ament_cmake_core)
Expand Down Expand Up @@ -44,7 +45,8 @@ target_link_libraries(${PROJECT_NAME}_library PUBLIC
rcutils::rcutils
rmw::rmw)
target_link_libraries(${PROJECT_NAME}_library PRIVATE
rcpputils::rcpputils)
rcpputils::rcpputils
rosidl_runtime_c::rosidl_runtime_c)
target_include_directories(${PROJECT_NAME}_library
PUBLIC
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
Expand Down Expand Up @@ -95,7 +97,8 @@ if(BUILD_TESTING)

ament_add_gmock(test_graph_cache test/test_graph_cache.cpp)
if(TARGET test_graph_cache)
target_link_libraries(test_graph_cache ${PROJECT_NAME}_library osrf_testing_tools_cpp::memory_tools)
target_link_libraries(test_graph_cache
${PROJECT_NAME}_library osrf_testing_tools_cpp::memory_tools rosidl_runtime_c::rosidl_runtime_c)
target_compile_definitions(test_graph_cache PUBLIC RCUTILS_ENABLE_FAULT_INJECTION)
endif()

Expand All @@ -106,7 +109,7 @@ if(BUILD_TESTING)

ament_add_gmock(test_qos test/test_qos.cpp)
if(TARGET test_qos)
target_link_libraries(test_qos ${PROJECT_NAME}_library osrf_testing_tools_cpp::memory_tools)
target_link_libraries(test_qos ${PROJECT_NAME}_library osrf_testing_tools_cpp::memory_tools rcpputils::rcpputils)
endif()

ament_add_gmock(test_time_utils test/test_time_utils.cpp)
Expand All @@ -123,7 +126,7 @@ if(BUILD_TESTING)

add_performance_test(benchmark_graph_cache test/benchmark/benchmark_graph_cache.cpp)
if(TARGET benchmark_graph_cache)
target_link_libraries(benchmark_graph_cache ${PROJECT_NAME}_library)
target_link_libraries(benchmark_graph_cache ${PROJECT_NAME}_library rosidl_runtime_c::rosidl_runtime_c)
endif()
endif()

Expand Down
60 changes: 58 additions & 2 deletions rmw_dds_common/include/rmw_dds_common/graph_cache.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,18 +78,35 @@ class GraphCache
* @{
*/

/// Add a data writer.
/// Add a data writer based on discovery.
/**
* \param writer_gid GUID of the data writer.
* \param topic_name Name of the DDS topic for this data writer.
* \param type_name Type name of the DDS topic for this data writer.
* \param type_hash Hash of the description of the topic type.
* \param participant_gid GUID of the participant.
* \param qos QoS profile of the data writer.
* \return `true` if the cache was updated, `false` if the data writer
* was already present.
*/
RMW_DDS_COMMON_PUBLIC
bool
add_writer(
const rmw_gid_t & writer_gid,
const std::string & topic_name,
const std::string & type_name,
const rosidl_type_hash_t & type_hash,
const rmw_gid_t & participant_gid,
const rmw_qos_profile_t & qos);

/// Add a data writer based on discovery.
/**
* See add_reader with rosidl_type_hash_t, whose other parameters match these.
*/
RMW_DDS_COMMON_PUBLIC
RCUTILS_DEPRECATED_WITH_MSG(
"Migrate to using the version of this function taking a type hash.")
bool
add_writer(
const rmw_gid_t & writer_gid,
const std::string & topic_name,
Expand All @@ -102,13 +119,30 @@ class GraphCache
* \param reader_gid GUID of the The data reader.
* \param topic_name Name of the DDS topic for this data reader.
* \param type_name Type name of the DDS topic for this data reader.
* \param type_hash Hash of the description of the topic type.
* \param participant_gid GUID of the participant.
* \param qos QoS profile of the data reader.
* \return `true` if the cache was updated, `false` if the data reader
* was already present.
*/
RMW_DDS_COMMON_PUBLIC
bool
add_reader(
const rmw_gid_t & reader_gid,
const std::string & topic_name,
const std::string & type_name,
const rosidl_type_hash_t & type_hash,
const rmw_gid_t & participant_gid,
const rmw_qos_profile_t & qos);

/// Add a data reader based on discovery.
/**
* See add_reader with rosidl_type_hash_t, whose other parameters match these.
*/
RMW_DDS_COMMON_PUBLIC
RCUTILS_DEPRECATED_WITH_MSG(
"Migrate to using the version of this function taking a type hash.")
bool
add_reader(
const rmw_gid_t & reader_gid,
const std::string & topic_name,
Expand All @@ -121,6 +155,7 @@ class GraphCache
* \param gid GUID of the entity.
* \param topic_name Name of the DDS topic for this data reader.
* \param type_name Type name of the DDS topic for this entity
* \param type_hash Hash of the description of the topic type.
* \param participant_gid GUID of the participant.
* \param qos QoS profile of the entity.
* \param is_reader Whether the entity is a data reader or a writer.
Expand All @@ -129,6 +164,23 @@ class GraphCache
*/
RMW_DDS_COMMON_PUBLIC
bool
add_entity(
const rmw_gid_t & gid,
const std::string & topic_name,
const std::string & type_name,
const rosidl_type_hash_t & type_hash,
const rmw_gid_t & participant_gid,
const rmw_qos_profile_t & qos,
bool is_reader);

/// Add a data reader or writer.
/**
* See add_entity with rosidl_type_hash_t, whose other parameters match these.
*/
RMW_DDS_COMMON_PUBLIC
RCUTILS_DEPRECATED_WITH_MSG(
"Migrate to using the version of this function taking a type hash.")
bool
add_entity(
const rmw_gid_t & gid,
const std::string & topic_name,
Expand Down Expand Up @@ -541,8 +593,10 @@ struct EntityInfo
{
/// Topic name.
std::string topic_name;
/// Topic type.
/// Topic type name.
std::string topic_type;
/// Topic type hash.
rosidl_type_hash_t topic_type_hash;
/// Participant gid.
rmw_gid_t participant_gid;
/// Quality of service of the topic.
Expand All @@ -552,10 +606,12 @@ struct EntityInfo
EntityInfo(
const std::string & topic_name,
const std::string & topic_type,
const rosidl_type_hash_t & topic_type_hash,
const rmw_gid_t & participant_gid,
const rmw_qos_profile_t & qos)
: topic_name(topic_name),
topic_type(topic_type),
topic_type_hash(topic_type_hash),
participant_gid(participant_gid),
qos(qos)
{}
Expand Down
31 changes: 31 additions & 0 deletions rmw_dds_common/include/rmw_dds_common/qos.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#define RMW_DDS_COMMON__QOS_HPP_

#include <functional>
#include <string>

#include "rmw/qos_profiles.h"
#include "rmw/topic_endpoint_info_array.h"
Expand Down Expand Up @@ -224,6 +225,36 @@ RMW_DDS_COMMON_PUBLIC
rmw_qos_profile_t
qos_profile_update_best_available_for_services(const rmw_qos_profile_t & qos_profile);

/// Parse USER_DATA "key=value;key=value;"" encoding, finding value of key "typehash"
/**
* \param[in] user_data USER_DATA qos raw bytes
* \param[in] user_data_size Length of user_data
* \param[out] type_hash_out Filled with type hash data if found, or to zero value if key not found
* \return RMW_RET_OK if key parsed successfully, or if key not found
* \return RMW_RET_INVALID_ARGUMENT if user_data is null
* \return RMW_RET_ERROR if typehash key found, but value could not be parsed
*/
RMW_DDS_COMMON_PUBLIC
rmw_ret_t
parse_type_hash_from_user_data(
const uint8_t * user_data,
size_t user_data_size,
rosidl_type_hash_t & type_hash_out);

/// Encode type hash as "typehash=hash_string;" for use in USER_DATA QoS
/**
* \param[in] type_hash Type hash value to encode
* \param[out] string_out On success, will be set to "typehash=stringified_type_hash;"
* If type_hash's version is 0, string_out will be set to empty
* \return RMW_RET_OK on success, including empty string for unset version
* \return RMW_RET_BAD_ALLOC if memory allocation fails
*/
RMW_DDS_COMMON_PUBLIC
rmw_ret_t
encode_type_hash_for_user_data_qos(
const rosidl_type_hash_t & type_hash,
std::string & string_out);

} // namespace rmw_dds_common

#endif // RMW_DDS_COMMON__QOS_HPP_
1 change: 1 addition & 0 deletions rmw_dds_common/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
<depend>rcutils</depend>
<depend>rcpputils</depend>
<depend>rmw</depend>
<depend>rosidl_runtime_c</depend>
<depend>rosidl_runtime_cpp</depend>

<test_depend>ament_cmake_gmock</test_depend>
Expand Down
69 changes: 67 additions & 2 deletions rmw_dds_common/src/graph_cache.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,40 +67,77 @@ GraphCache::add_writer(
const rmw_gid_t & gid,
const std::string & topic_name,
const std::string & type_name,
const rosidl_type_hash_t & type_hash,
const rmw_gid_t & participant_gid,
const rmw_qos_profile_t & qos)
{
std::lock_guard<std::mutex> guard(mutex_);
auto pair = data_writers_.emplace(
std::piecewise_construct,
std::forward_as_tuple(gid),
std::forward_as_tuple(topic_name, type_name, participant_gid, qos));
std::forward_as_tuple(topic_name, type_name, type_hash, participant_gid, qos));
GRAPH_CACHE_CALL_ON_CHANGE_CALLBACK_IF(this, pair.second);
return pair.second;
}

bool
GraphCache::add_writer(
const rmw_gid_t & gid,
const std::string & topic_name,
const std::string & type_name,
const rmw_gid_t & participant_gid,
const rmw_qos_profile_t & qos)
{
return this->add_writer(
gid,
topic_name,
type_name,
rosidl_get_zero_initialized_type_hash(),
participant_gid,
qos);
}

bool
GraphCache::add_reader(
const rmw_gid_t & gid,
const std::string & topic_name,
const std::string & type_name,
const rosidl_type_hash_t & type_hash,
const rmw_gid_t & participant_gid,
const rmw_qos_profile_t & qos)
{
std::lock_guard<std::mutex> guard(mutex_);
auto pair = data_readers_.emplace(
std::piecewise_construct,
std::forward_as_tuple(gid),
std::forward_as_tuple(topic_name, type_name, participant_gid, qos));
std::forward_as_tuple(topic_name, type_name, type_hash, participant_gid, qos));
GRAPH_CACHE_CALL_ON_CHANGE_CALLBACK_IF(this, pair.second);
return pair.second;
}

bool
GraphCache::add_reader(
const rmw_gid_t & gid,
const std::string & topic_name,
const std::string & type_name,
const rmw_gid_t & participant_gid,
const rmw_qos_profile_t & qos)
{
return this->add_reader(
gid,
topic_name,
type_name,
rosidl_get_zero_initialized_type_hash(),
participant_gid,
qos);
}

bool
GraphCache::add_entity(
const rmw_gid_t & gid,
const std::string & topic_name,
const std::string & type_name,
const rosidl_type_hash_t & type_hash,
const rmw_gid_t & participant_gid,
const rmw_qos_profile_t & qos,
bool is_reader)
Expand All @@ -110,17 +147,38 @@ GraphCache::add_entity(
gid,
topic_name,
type_name,
type_hash,
participant_gid,
qos);
}
return this->add_writer(
gid,
topic_name,
type_name,
type_hash,
participant_gid,
qos);
}

bool
GraphCache::add_entity(
const rmw_gid_t & gid,
const std::string & topic_name,
const std::string & type_name,
const rmw_gid_t & participant_gid,
const rmw_qos_profile_t & qos,
bool is_reader)
{
return this->add_entity(
gid,
topic_name,
type_name,
rosidl_get_zero_initialized_type_hash(),
participant_gid,
qos,
is_reader);
}

bool
GraphCache::remove_writer(const rmw_gid_t & gid)
{
Expand Down Expand Up @@ -570,6 +628,13 @@ __get_entities_info_by_topic(
return ret;
}

ret = rmw_topic_endpoint_info_set_topic_type_hash(
&endpoint_info,
&entity_pair.second.topic_type_hash);
if (RMW_RET_OK != ret) {
return ret;
}

ret = rmw_topic_endpoint_info_set_endpoint_type(
&endpoint_info,
is_reader ? RMW_ENDPOINT_SUBSCRIPTION : RMW_ENDPOINT_PUBLISHER);
Expand Down
Loading