Increase coverage of publisher/subscription API (#1325)

* Increase coverage of publisher/subscription API

Signed-off-by: Stephen Brawner <brawner@gmail.com>

* PR Feedback

Signed-off-by: Stephen Brawner <brawner@gmail.com>
This commit is contained in:
brawner 2020-09-24 13:58:39 -07:00
parent b451425ce6
commit 5fd6e2340a
3 changed files with 299 additions and 3 deletions

View file

@ -317,12 +317,13 @@ endif()
ament_add_gtest(test_publisher rclcpp/test_publisher.cpp)
if(TARGET test_publisher)
ament_target_dependencies(test_publisher
"rcl"
"rmw"
"rosidl_runtime_cpp"
"rosidl_typesupport_cpp"
"test_msgs"
)
target_link_libraries(test_publisher ${PROJECT_NAME})
target_link_libraries(test_publisher ${PROJECT_NAME} mimick)
endif()
ament_add_gtest(test_publisher_subscription_count_api rclcpp/test_publisher_subscription_count_api.cpp)
if(TARGET test_publisher_subscription_count_api)
@ -404,7 +405,7 @@ if(TARGET test_subscription)
"rosidl_typesupport_cpp"
"test_msgs"
)
target_link_libraries(test_subscription ${PROJECT_NAME})
target_link_libraries(test_subscription ${PROJECT_NAME} mimick)
endif()
ament_add_gtest(test_subscription_publisher_count_api rclcpp/test_subscription_publisher_count_api.cpp)
if(TARGET test_subscription_publisher_count_api)

View file

@ -16,11 +16,17 @@
#include <string>
#include <memory>
#include <utility>
#include <vector>
#include "rcl/publisher.h"
#include "rclcpp/exceptions.hpp"
#include "rclcpp/rclcpp.hpp"
#include "../mocking_utils/patch.hpp"
#include "../utils/rclcpp_gtest_macros.hpp"
#include "test_msgs/msg/empty.hpp"
class TestPublisher : public ::testing::Test
@ -259,3 +265,182 @@ TEST_F(TestPublisher, basic_getters) {
EXPECT_EQ(publisher, publisher_rmw_gid);
}
}
TEST_F(TestPublisher, rcl_publisher_init_error) {
initialize();
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_publisher_init, RCL_RET_ERROR);
EXPECT_THROW(
node->create_publisher<test_msgs::msg::Empty>("topic", 10).reset(),
rclcpp::exceptions::RCLError);
}
TEST_F(TestPublisher, rcl_publisher_get_rmw_handle_error) {
initialize();
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_publisher_get_rmw_handle, nullptr);
RCLCPP_EXPECT_THROW_EQ(
node->create_publisher<test_msgs::msg::Empty>("topic", 10),
std::runtime_error("failed to get rmw handle: error not set"));
}
TEST_F(TestPublisher, rcl_publisher_get_gid_for_publisher_error) {
initialize();
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rmw_get_gid_for_publisher, RMW_RET_ERROR);
RCLCPP_EXPECT_THROW_EQ(
node->create_publisher<test_msgs::msg::Empty>("topic", 10),
std::runtime_error("failed to get publisher gid: error not set"));
}
TEST_F(TestPublisher, rcl_publisher_fini_error) {
initialize();
auto mock = mocking_utils::inject_on_return("lib:rclcpp", rcl_publisher_fini, RCL_RET_ERROR);
auto publisher = node->create_publisher<test_msgs::msg::Empty>("topic", 10);
ASSERT_EQ(1, publisher.use_count());
// Failure in rcl_publisher_fini should just log error
EXPECT_NO_THROW(publisher.reset());
}
TEST_F(TestPublisher, rcl_publisher_get_options_error) {
initialize();
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_publisher_get_options, nullptr);
auto publisher = node->create_publisher<test_msgs::msg::Empty>("topic", 10);
RCLCPP_EXPECT_THROW_EQ(
publisher->get_queue_size(),
std::runtime_error("failed to get publisher options: error not set"));
}
TEST_F(TestPublisher, rcl_publisher_get_subscription_count_publisher_invalid) {
initialize();
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_publisher_get_subscription_count, RCL_RET_PUBLISHER_INVALID);
auto publisher = node->create_publisher<test_msgs::msg::Empty>("topic", 10);
EXPECT_THROW(
publisher->get_subscription_count(),
rclcpp::exceptions::RCLError);
}
TEST_F(TestPublisher, rcl_publisher_get_actual_qos_error) {
initialize();
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_publisher_get_actual_qos, nullptr);
auto publisher = node->create_publisher<test_msgs::msg::Empty>("topic", 10);
RCLCPP_EXPECT_THROW_EQ(
publisher->get_actual_qos(),
std::runtime_error("failed to get qos settings: error not set"));
}
TEST_F(TestPublisher, publishers_equal_rmw_compare_gids_error) {
initialize();
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rmw_compare_gids_equal, RMW_RET_ERROR);
const auto publisher = node->create_publisher<test_msgs::msg::Empty>("topic", 10);
const rmw_gid_t * gid = nullptr;
auto throwing_fn = [publisher, gid]()
{
// The == operator is expected to throw here, but this lambda avoids unused result warning
return (*publisher.get() == gid) ? true : false;
};
RCLCPP_EXPECT_THROW_EQ(
throwing_fn(),
std::runtime_error("failed to compare gids: error not set"));
}
TEST_F(TestPublisher, intra_process_publish_failures) {
initialize();
rclcpp::PublisherOptionsWithAllocator<std::allocator<void>> options;
options.use_intra_process_comm = rclcpp::IntraProcessSetting::Enable;
auto publisher = node->create_publisher<test_msgs::msg::Empty>("topic", 10, options);
auto msg_unique = std::make_unique<test_msgs::msg::Empty>();
EXPECT_NO_THROW(publisher->publish(std::move(msg_unique)));
rclcpp::SerializedMessage serialized_msg;
RCLCPP_EXPECT_THROW_EQ(
publisher->publish(serialized_msg),
std::runtime_error("storing serialized messages in intra process is not supported yet"));
std::allocator<void> allocator;
{
rclcpp::LoanedMessage<test_msgs::msg::Empty> loaned_msg(*publisher, allocator);
RCLCPP_EXPECT_THROW_EQ(
publisher->publish(std::move(loaned_msg)),
std::runtime_error("storing loaned messages in intra process is not supported yet"));
}
{
rclcpp::LoanedMessage<test_msgs::msg::Empty> loaned_msg(*publisher, allocator);
loaned_msg.release();
RCLCPP_EXPECT_THROW_EQ(
publisher->publish(std::move(loaned_msg)),
std::runtime_error("loaned message is not valid"));
}
}
TEST_F(TestPublisher, inter_process_publish_failures) {
initialize();
rclcpp::PublisherOptionsWithAllocator<std::allocator<void>> options;
options.use_intra_process_comm = rclcpp::IntraProcessSetting::Disable;
auto publisher = node->create_publisher<test_msgs::msg::Empty>("topic", 10, options);
auto msg_unique = std::make_unique<test_msgs::msg::Empty>();
EXPECT_NO_THROW(publisher->publish(std::move(msg_unique)));
{
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_publish, RCL_RET_PUBLISHER_INVALID);
test_msgs::msg::Empty msg;
EXPECT_THROW(publisher->publish(msg), rclcpp::exceptions::RCLError);
}
rclcpp::SerializedMessage serialized_msg;
EXPECT_NO_THROW(publisher->publish(serialized_msg));
{
// Using 'self' instead of 'lib:rclcpp' because `rcl_publish_serialized_message` is entirely
// defined in a header
auto mock = mocking_utils::patch_and_return(
"self", rcl_publish_serialized_message, RCL_RET_ERROR);
EXPECT_THROW(publisher->publish(serialized_msg), rclcpp::exceptions::RCLError);
}
std::allocator<void> allocator;
rclcpp::LoanedMessage<test_msgs::msg::Empty> loaned_msg(*publisher, allocator);
EXPECT_NO_THROW(publisher->publish(std::move(loaned_msg)));
}
template<typename MessageT, typename AllocatorT = std::allocator<void>>
class TestPublisherProtectedMethods : public rclcpp::Publisher<MessageT, AllocatorT>
{
public:
using rclcpp::Publisher<MessageT, AllocatorT>::Publisher;
void publish_loaned_message(MessageT * msg)
{
this->do_loaned_message_publish(msg);
}
};
TEST_F(TestPublisher, do_loaned_message_publish_error) {
initialize();
using PublisherT = TestPublisherProtectedMethods<test_msgs::msg::Empty, std::allocator<void>>;
auto publisher =
node->create_publisher<test_msgs::msg::Empty, std::allocator<void>, PublisherT>("topic", 10);
auto msg = std::make_shared<test_msgs::msg::Empty>();
{
// Using 'self' instead of 'lib:rclcpp' because `rcl_publish_loaned_message` is entirely
// defined in a header
auto mock = mocking_utils::patch_and_return(
"self", rcl_publish_loaned_message, RCL_RET_PUBLISHER_INVALID);
EXPECT_THROW(publisher->publish_loaned_message(msg.get()), rclcpp::exceptions::RCLError);
}
}
TEST_F(TestPublisher, run_event_handlers) {
initialize();
auto publisher = node->create_publisher<test_msgs::msg::Empty>("topic", 10);
for (const auto & handler : publisher->get_event_handlers()) {
EXPECT_NO_THROW(handler->execute());
}
}

View file

@ -23,6 +23,9 @@
#include "rclcpp/exceptions.hpp"
#include "rclcpp/rclcpp.hpp"
#include "../mocking_utils/patch.hpp"
#include "../utils/rclcpp_gtest_macros.hpp"
#include "test_msgs/msg/empty.hpp"
using namespace std::chrono_literals;
@ -150,7 +153,19 @@ TEST_F(TestSubscription, construction_and_destruction) {
(void)msg;
};
{
auto sub = node->create_subscription<Empty>("topic", 10, callback);
constexpr size_t depth = 10u;
auto sub = node->create_subscription<Empty>("topic", depth, callback);
EXPECT_NE(nullptr, sub->get_subscription_handle());
// Converting to base class was necessary for the compiler to choose the const version of
// get_subscription_handle()
const rclcpp::SubscriptionBase * const_sub = sub.get();
EXPECT_NE(nullptr, const_sub->get_subscription_handle());
EXPECT_FALSE(sub->use_take_shared_method());
EXPECT_NE(nullptr, sub->get_message_type_support_handle().typesupport_identifier);
EXPECT_NE(nullptr, sub->get_message_type_support_handle().data);
EXPECT_EQ(depth, sub->get_actual_qos().get_rmw_qos_profile().depth);
}
{
@ -229,6 +244,21 @@ TEST_F(TestSubscription, various_creation_signatures) {
node, "topic", 42, cb, rclcpp::SubscriptionOptions());
(void)sub;
}
{
rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void>> options;
options.allocator = std::make_shared<std::allocator<void>>();
EXPECT_NE(nullptr, options.get_allocator());
auto sub = rclcpp::create_subscription<Empty>(
node, "topic", 42, cb, options);
(void)sub;
}
{
rclcpp::SubscriptionOptionsBase options_base;
rclcpp::SubscriptionOptionsWithAllocator<std::allocator<void>> options(options_base);
auto sub = rclcpp::create_subscription<Empty>(
node, "topic", 42, cb, options);
(void)sub;
}
}
/*
@ -329,6 +359,86 @@ TEST_F(TestSubscription, take_serialized) {
}
}
TEST_F(TestSubscription, rcl_subscription_init_error) {
initialize();
auto callback = [](std::shared_ptr<const test_msgs::msg::Empty>) {};
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_subscription_init, RCL_RET_TOPIC_NAME_INVALID);
// reset() is not needed for triggering exception, just to avoid an unused return value warning
EXPECT_THROW(
node->create_subscription<test_msgs::msg::Empty>("topic", 10, callback).reset(),
rclcpp::exceptions::RCLError);
}
TEST_F(TestSubscription, rcl_subscription_fini_error) {
initialize();
auto callback = [](std::shared_ptr<const test_msgs::msg::Empty>) {};
auto mock = mocking_utils::inject_on_return(
"lib:rclcpp", rcl_subscription_fini, RCL_RET_ERROR);
// Cleanup just fails, no exception expected
EXPECT_NO_THROW(
node->create_subscription<test_msgs::msg::Empty>("topic", 10, callback).reset());
}
TEST_F(TestSubscription, rcl_subscription_get_actual_qos_error) {
initialize();
auto callback = [](std::shared_ptr<const test_msgs::msg::Empty>) {};
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_subscription_get_actual_qos, nullptr);
auto sub = node->create_subscription<test_msgs::msg::Empty>("topic", 10, callback);
RCLCPP_EXPECT_THROW_EQ(
sub->get_actual_qos(), std::runtime_error("failed to get qos settings: error not set"));
}
TEST_F(TestSubscription, rcl_take_type_erased_error) {
initialize();
auto callback = [](std::shared_ptr<const test_msgs::msg::Empty>) {};
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_take, RCL_RET_ERROR);
auto sub = node->create_subscription<test_msgs::msg::Empty>("topic", 10, callback);
test_msgs::msg::Empty msg;
rclcpp::MessageInfo message_info;
EXPECT_THROW(sub->take_type_erased(&msg, message_info), rclcpp::exceptions::RCLError);
}
TEST_F(TestSubscription, rcl_take_serialized_message_error) {
initialize();
auto callback = [](std::shared_ptr<const test_msgs::msg::Empty>) {};
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_take_serialized_message, RCL_RET_ERROR);
auto sub = node->create_subscription<test_msgs::msg::Empty>("topic", 10, callback);
rclcpp::SerializedMessage msg;
rclcpp::MessageInfo message_info;
EXPECT_THROW(sub->take_serialized(msg, message_info), rclcpp::exceptions::RCLError);
}
TEST_F(TestSubscription, rcl_subscription_get_publisher_count_error) {
initialize();
auto callback = [](std::shared_ptr<const test_msgs::msg::Empty>) {};
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_subscription_get_publisher_count, RCL_RET_ERROR);
auto sub = node->create_subscription<test_msgs::msg::Empty>("topic", 10, callback);
EXPECT_THROW(sub->get_publisher_count(), rclcpp::exceptions::RCLError);
}
TEST_F(TestSubscription, handle_loaned_message) {
initialize();
auto callback = [](std::shared_ptr<const test_msgs::msg::Empty>) {};
auto sub = node->create_subscription<test_msgs::msg::Empty>("topic", 10, callback);
test_msgs::msg::Empty msg;
rclcpp::MessageInfo message_info;
EXPECT_NO_THROW(sub->handle_loaned_message(&msg, message_info));
}
/*
Testing subscription with intraprocess enabled and invalid QoS
*/