Skip to content

Commit

Permalink
Added tests to verify the output of rmw_get_info_by_topic functions
Browse files Browse the repository at this point in the history
Signed-off-by: Jaison Titus <jaisontj92@gmail.com>
  • Loading branch information
jaisontj committed Nov 25, 2019
1 parent 9150a43 commit 817d67f
Show file tree
Hide file tree
Showing 2 changed files with 103 additions and 2 deletions.
2 changes: 1 addition & 1 deletion rcl/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -112,7 +112,7 @@ function(test_target_function)
ENV ${rmw_implementation_env_var}
APPEND_LIBRARY_DIRS ${extra_lib_dirs}
LIBRARIES ${PROJECT_NAME}
AMENT_DEPENDENCIES ${rmw_implementation} "osrf_testing_tools_cpp"
AMENT_DEPENDENCIES ${rmw_implementation} "osrf_testing_tools_cpp" "test_msgs"
${AMENT_GTEST_ARGS}
)

Expand Down
103 changes: 102 additions & 1 deletion rcl/test/rcl/test_info_by_topic.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,11 +19,18 @@
#include <gtest/gtest.h>

#include <memory>
#include <string>

#include "rcl/error_handling.h"
#include "rcl/graph.h"
#include "rcl/rcl.h"

#include "rmw/topic_info_array.h"
#include "rmw/error_handling.h"

#include "test_msgs/msg/strings.h"
#include "rosidl_generator_c/string_functions.h"

#include "osrf_testing_tools_cpp/scope_exit.hpp"

#ifdef RMW_IMPLEMENTATION
Expand All @@ -43,9 +50,10 @@ class CLASSNAME (TestInfoByTopicFixture, RMW_IMPLEMENTATION) : public ::testing:
const char * test_graph_node_name = "test_graph_node";
std::unique_ptr<rmw_topic_info_array_t> topic_info_array;
const char * const topic_name = "valid_topic_name";

bool is_fastrtps;
void SetUp()
{
is_fastrtps = (std::string(rmw_get_implementation_identifier()).find("rmw_fastrtps") == 0);
rcl_ret_t ret;
rcl_init_options_t init_options = rcl_get_zero_initialized_init_options();
ret = rcl_init_options_init(&init_options, rcl_get_default_allocator());
Expand Down Expand Up @@ -100,6 +108,21 @@ class CLASSNAME (TestInfoByTopicFixture, RMW_IMPLEMENTATION) : public ::testing:
EXPECT_EQ(RCL_RET_OK, ret) << rcl_get_error_string().str;
delete this->old_context_ptr;
}

void assert_qos_equality(rmw_qos_profile_t qos_profile1, rmw_qos_profile_t qos_profile2)
{
EXPECT_EQ(qos_profile1.deadline.sec, qos_profile2.deadline.sec);
EXPECT_EQ(qos_profile1.deadline.nsec, qos_profile2.deadline.nsec);
EXPECT_EQ(qos_profile1.lifespan.sec, qos_profile2.lifespan.sec);
EXPECT_EQ(qos_profile1.lifespan.nsec, qos_profile2.lifespan.nsec);
EXPECT_EQ(qos_profile1.reliability, qos_profile2.reliability);
EXPECT_EQ(qos_profile1.liveliness, qos_profile2.liveliness);
EXPECT_EQ(qos_profile1.liveliness_lease_duration.sec,
qos_profile2.liveliness_lease_duration.sec);
EXPECT_EQ(qos_profile1.liveliness_lease_duration.nsec,
qos_profile2.liveliness_lease_duration.nsec);
EXPECT_EQ(qos_profile1.durability, qos_profile2.durability);
}
};

/*
Expand Down Expand Up @@ -275,3 +298,81 @@ TEST_F(CLASSNAME(TestInfoByTopicFixture, RMW_IMPLEMENTATION),
&allocator, this->topic_name, false, temp_info_array);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, ret);
}

TEST_F(CLASSNAME(TestInfoByTopicFixture, RMW_IMPLEMENTATION),
test_rcl_get_publishers_subscription_info_by_topic)
{
// This is implemented only in fastrtps currently.
if (!is_fastrtps) {
GTEST_SKIP();
}
rmw_qos_profile_t default_qos_profile;
default_qos_profile.history = RMW_QOS_POLICY_HISTORY_KEEP_LAST;
default_qos_profile.depth = 0;
default_qos_profile.reliability = RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT;
default_qos_profile.durability = RMW_QOS_POLICY_DURABILITY_VOLATILE;
default_qos_profile.lifespan = {10, 0};
default_qos_profile.deadline = {11, 0};
default_qos_profile.liveliness_lease_duration = {20, 0};
default_qos_profile.liveliness = RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC;

rcl_ret_t ret;
const rosidl_message_type_support_t * ts = ROSIDL_GET_MSG_TYPE_SUPPORT(test_msgs, msg, Strings);
rcl_allocator_t allocator = rcl_get_default_allocator();

rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
publisher_options.qos = default_qos_profile;
ret = rcl_publisher_init(
&publisher,
this->node_ptr,
ts,
this->topic_name,
&publisher_options);
ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;

rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
rcl_subscription_options_t subscription_options = rcl_subscription_get_default_options();
subscription_options.qos = default_qos_profile;
ret = rcl_subscription_init(
&subscription,
this->node_ptr,
ts,
this->topic_name,
&subscription_options);
ASSERT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
std::string fqdn = this->topic_name;
fqdn = "/" + fqdn;
// Get publishers info by topic
rmw_topic_info_array_t topic_info_array_pub = rmw_get_zero_initialized_topic_info_array();
ret = rcl_get_publishers_info_by_topic(this->node_ptr,
&allocator, fqdn.c_str(), false, &topic_info_array_pub);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(topic_info_array_pub.count, 1u) << "Expected one publisher";
rmw_topic_info_t topic_info_pub = topic_info_array_pub.info_array[0];
EXPECT_STREQ(topic_info_pub.node_name, this->test_graph_node_name);
EXPECT_STREQ(topic_info_pub.node_namespace, "/");
EXPECT_STREQ(topic_info_pub.topic_type, "test_msgs::msg::dds_::Strings_");
assert_qos_equality(topic_info_pub.qos_profile, default_qos_profile);

rmw_topic_info_array_t topic_info_array_sub = rmw_get_zero_initialized_topic_info_array();
ret = rcl_get_subscriptions_info_by_topic(this->node_ptr,
&allocator, fqdn.c_str(), false, &topic_info_array_sub);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
EXPECT_EQ(topic_info_array_sub.count, 1u) << "Expected one subscription";
rmw_topic_info_t topic_info_sub = topic_info_array_sub.info_array[0];
EXPECT_STREQ(topic_info_sub.node_name, this->test_graph_node_name);
EXPECT_STREQ(topic_info_sub.node_namespace, "/");
EXPECT_STREQ(topic_info_sub.topic_type, "test_msgs::msg::dds_::Strings_");
assert_qos_equality(topic_info_sub.qos_profile, default_qos_profile);

// clean up
rmw_ret_t rmw_ret = rmw_topic_info_array_fini(&topic_info_array_pub, &allocator);
EXPECT_EQ(rmw_ret, RMW_RET_OK) << rmw_get_error_string().str;
rmw_ret = rmw_topic_info_array_fini(&topic_info_array_sub, &allocator);
EXPECT_EQ(rmw_ret, RMW_RET_OK) << rmw_get_error_string().str;
ret = rcl_subscription_fini(&subscription, this->node_ptr);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
ret = rcl_publisher_fini(&publisher, this->node_ptr);
EXPECT_EQ(ret, RCL_RET_OK) << rcl_get_error_string().str;
}

0 comments on commit 817d67f

Please sign in to comment.