Skip to content
This repository has been archived by the owner on Oct 7, 2021. It is now read-only.

Commit

Permalink
Stubs for rmw_get_publishers_info_by_topic and rmw_get_subscriptions_…
Browse files Browse the repository at this point in the history
…info_by_topic (#289)

Signed-off-by: Jaison Titus <jaisontj92@gmail.com>
Signed-off-by: Miaofei Mei <ameision@hotmail.com>
  • Loading branch information
jaisontj authored and ivanpauno committed Jan 14, 2020
1 parent 584aa8c commit d2dbf27
Show file tree
Hide file tree
Showing 6 changed files with 96 additions and 49 deletions.
1 change: 1 addition & 0 deletions rmw_opensplice_cpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -79,6 +79,7 @@ add_library(rmw_opensplice_cpp SHARED
src/rmw_wait_set.cpp
src/serialization_format.cpp
src/types.cpp
src/rmw_get_topic_endpoint_info.cpp
)
ament_target_dependencies(rmw_opensplice_cpp
"rcpputils"
Expand Down
45 changes: 45 additions & 0 deletions rmw_opensplice_cpp/src/rmw_get_topic_endpoint_info.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
// Copyright 2019 Amazon.com, Inc. or its affiliates. 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/error_handling.h"
#include "rmw/get_topic_endpoint_info.h"
#include "rmw/topic_endpoint_info_array.h"

#include "identifier.hpp"
#include "types.hpp"

extern "C"
{
rmw_ret_t
rmw_get_publishers_info_by_topic(
const rmw_node_t * /* unused_param */,
rcutils_allocator_t * /* unused_param */,
const char * /* unused_param */,
bool /* unused_param */,
rmw_topic_endpoint_info_array_t * /* unused_param */)
{
return RMW_RET_UNSUPPORTED;
}

rmw_ret_t
rmw_get_subscriptions_info_by_topic(
const rmw_node_t * /* unused_param */,
rcutils_allocator_t * /* unused_param */,
const char * /* unused_param */,
bool /* unused_param */,
rmw_topic_endpoint_info_array_t * /* unused_param */)
{
return RMW_RET_UNSUPPORTED;
}
} // extern "C"
20 changes: 10 additions & 10 deletions rmw_opensplice_cpp/src/rmw_node_info_and_types.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -38,10 +38,10 @@ extern "C"
* Check to see if a node name and namespace match the user data QoS policy
* of a node.
*
* @param user_data_qos to inspect
* @param node_name to match
* @param node_namespace to match
* @return true if match
* \param user_data_qos to inspect
* \param node_name to match
* \param node_namespace to match
* \return true if match
*/
bool
__is_node_match(
Expand Down Expand Up @@ -69,12 +69,12 @@ __is_node_match(
* Get a DDS GUID key for the discovered participant which matches the
* node_name and node_namepace supplied.
*
* @param node_info to discover nodes
* @param node_name to match
* @param node_namespace to match
* @param key [out] key (an InstanceHandle) that matches the node name and namespace
* \param node_info to discover nodes
* \param node_name to match
* \param node_namespace to match
* \param key [out] key (an InstanceHandle) that matches the node name and namespace
*
* @return RMW_RET_OK if success, ERROR otherwise
* \return RMW_RET_OK if success, ERROR otherwise
*/
rmw_ret_t
__get_key(
Expand All @@ -93,7 +93,7 @@ __get_key(

DDS::DomainParticipantQos dpqos;
auto dds_ret = participant->get_qos(dpqos);
// @todo: ross-desmond implement self discovery
// \todo: ross-desmond implement self discovery
if (dds_ret == DDS::RETCODE_OK && __is_node_match(dpqos.user_data, node_name, node_namespace)) {
key = node_info->participant->get_instance_handle();
return RMW_RET_OK;
Expand Down
58 changes: 29 additions & 29 deletions rmw_opensplice_cpp/src/topic_cache.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,15 +53,15 @@ class TopicCache
typedef std::map<GUID_t, TopicInfo> TopicGuidToInfo;

/**
* @return a map of topic name to the vector of topic types used.
* \return a map of topic name to the vector of topic types used.
*/
const TopicGuidToInfo & getTopicGuidToInfo() const
{
return topic_guid_to_info_;
}

/**
* @return a map of participant guid to the vector of topic names used.
* \return a map of participant guid to the vector of topic names used.
*/
const ParticipantToTopicGuidMap & getParticipantToTopicGuidMap() const
{
Expand All @@ -71,10 +71,10 @@ class TopicCache
/**
* Add a topic based on discovery.
*
* @param participant_guid
* @param topic_name
* @param type_name
* @return true if a change has been recorded
* \param participant_guid
* \param topic_name
* \param type_name
* \return true if a change has been recorded
*/
bool addTopic(
const GUID_t & participant_guid,
Expand All @@ -101,43 +101,43 @@ class TopicCache

/**
* Get topic info based on the topic guid
* @param topic_guid to search
* @param topic_info [out] result
* @return true if it exists
* \param topic_guid to search
* \param topic_endpoint_info [out] result
* \return true if it exists
*/
bool getTopic(const GUID_t & topic_guid, TopicInfo & topic_info) const
bool getTopic(const GUID_t & topic_guid, TopicInfo & topic_endpoint_info) const
{
auto topic_info_it = topic_guid_to_info_.find(topic_guid);
if (topic_info_it == topic_guid_to_info_.end()) {
auto topic_endpoint_info_it = topic_guid_to_info_.find(topic_guid);
if (topic_endpoint_info_it == topic_guid_to_info_.end()) {
RCUTILS_LOG_DEBUG_NAMED(
"rmw_opensplice_shared_cpp",
"topic not available.");
return false;
}
topic_info = topic_info_it->second;
topic_endpoint_info = topic_endpoint_info_it->second;
return true;
}

/**
* Remove a topic based on discovery.
*
* @param guid
* @return true if a change has been recorded
* \param guid
* \return true if a change has been recorded
*/
bool removeTopic(const GUID_t & topic_guid)
{
auto topic_info_it = topic_guid_to_info_.find(topic_guid);
if (topic_info_it == topic_guid_to_info_.end()) {
auto topic_endpoint_info_it = topic_guid_to_info_.find(topic_guid);
if (topic_endpoint_info_it == topic_guid_to_info_.end()) {
RCUTILS_LOG_DEBUG_NAMED(
"rmw_opensplice_shared_cpp",
"unexpected topic removal.");
return false;
}

std::string topic_name = topic_info_it->second.name;
std::string type_name = topic_info_it->second.type;
std::string topic_name = topic_endpoint_info_it->second.name;
std::string type_name = topic_endpoint_info_it->second.type;

auto participant_guid = topic_info_it->second.participant_guid;
auto participant_guid = topic_endpoint_info_it->second.participant_guid;
auto participant_to_topic_guid = participant_to_topic_guids_.find(participant_guid);
if (participant_to_topic_guid == participant_to_topic_guids_.end()) {
RCUTILS_LOG_WARN_NAMED(
Expand All @@ -158,7 +158,7 @@ class TopicCache
return false;
}

topic_guid_to_info_.erase(topic_info_it);
topic_guid_to_info_.erase(topic_endpoint_info_it);
participant_to_topic_guid->second.erase(topic_guid_to_remove);
if (participant_to_topic_guids_.empty()) {
participant_to_topic_guids_.erase(participant_to_topic_guid);
Expand All @@ -169,8 +169,8 @@ class TopicCache
/**
* Get topic types by guid.
*
* @param participant_guid to find topic types
* @return topic types corresponding to that guid
* \param participant_guid to find topic types
* \return topic types corresponding to that guid
*/
TopicsTypes getTopicTypesByGuid(const GUID_t & participant_guid)
{
Expand All @@ -182,16 +182,16 @@ class TopicCache
}

for (auto & topic_guid : participant_to_topic_guids->second) {
auto topic_info = topic_guid_to_info_.find(topic_guid);
if (topic_info == topic_guid_to_info_.end()) {
auto topic_endpoint_info = topic_guid_to_info_.find(topic_guid);
if (topic_endpoint_info == topic_guid_to_info_.end()) {
continue;
}
auto topic_name = topic_info->second.name;
auto topic_name = topic_endpoint_info->second.name;
auto topic_entry = topics_types.find(topic_name);
if (topic_entry == topics_types.end()) {
topics_types[topic_name] = std::set<std::string>();
}
topics_types[topic_name].insert(topic_info->second.type);
topics_types[topic_name].insert(topic_endpoint_info->second.type);
}
return topics_types;
}
Expand All @@ -215,8 +215,8 @@ class TopicCache
/**
* Helper function to initialize the set inside a participant map.
*
* @param map
* @param participant_guid
* \param map
* \param participant_guid
*/
void initializeParticipantMap(
ParticipantToTopicGuidMap & map,
Expand Down
7 changes: 4 additions & 3 deletions rmw_opensplice_cpp/src/types.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -213,9 +213,10 @@ void CustomDataReaderListener::remove_information(
const EndPointType endpoint_type)
{
if (print_discovery_logging_) {
TopicCache<DDS::InstanceHandle_t>::TopicInfo topic_info;
if (topic_cache.getTopic(topic, topic_info)) {
print_discovery_logging("-", topic_info.name, topic_info.type, endpoint_type);
TopicCache<DDS::InstanceHandle_t>::TopicInfo topic_endpoint_info;
if (topic_cache.getTopic(topic, topic_endpoint_info)) {
print_discovery_logging("-", topic_endpoint_info.name, topic_endpoint_info.type,
endpoint_type);
}
}
topic_cache.removeTopic(topic);
Expand Down
14 changes: 7 additions & 7 deletions rmw_opensplice_cpp/src/types.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,11 +111,11 @@ class CustomDataReaderListener
/**
* Add topic pub/sub information to discovery cache.
*
* @param participant the topic is related to
* @param topic the topic reader/writer unique id
* @param topic_name the topic name
* @param topic_type the topic type
* @param endpoint_type the endpoint type of this topic instance
* \param participant the topic is related to
* \param topic the topic reader/writer unique id
* \param topic_name the topic name
* \param topic_type the topic type
* \param endpoint_type the endpoint type of this topic instance
*/
void add_information(
const DDS::InstanceHandle_t & participant,
Expand All @@ -126,8 +126,8 @@ class CustomDataReaderListener

/**
* Remove topic pub/sub information from the discovery cache.
* @param topic the topic reader/writer unique id
* @param endpoint_type the endpoint type of this topic instance
* \param topic the topic reader/writer unique id
* \param endpoint_type the endpoint type of this topic instance
*/
void remove_information(
const DDS::InstanceHandle_t & topic,
Expand Down

0 comments on commit d2dbf27

Please sign in to comment.