Skip to content

Commit

Permalink
Add unit tests for qos and qos_event files (#1352)
Browse files Browse the repository at this point in the history
* Add unit tests for qos and qos_event files

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

* PR Feedback

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

* Address PR Feedback

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

* Fix windows CI

Signed-off-by: Stephen Brawner <brawner@gmail.com>
  • Loading branch information
brawner committed Oct 8, 2020
1 parent 517366f commit 9e0c964
Show file tree
Hide file tree
Showing 4 changed files with 229 additions and 2 deletions.
1 change: 1 addition & 0 deletions rclcpp/include/rclcpp/qos.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
namespace rclcpp
{

RCLCPP_PUBLIC
std::string qos_policy_name_from_kind(rmw_qos_policy_kind_t policy_kind);

/// QoS initialization values, cannot be created directly, use KeepAll or KeepLast instead.
Expand Down
1 change: 1 addition & 0 deletions rclcpp/test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -361,6 +361,7 @@ if(TARGET test_qos_event)
)
target_link_libraries(test_qos_event
${PROJECT_NAME}
mimick
)
endif()
ament_add_gtest(test_rate rclcpp/test_rate.cpp)
Expand Down
124 changes: 124 additions & 0 deletions rclcpp/test/rclcpp/test_qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@

#include "rclcpp/qos.hpp"

#include "rmw/types.h"

TEST(TestQoS, equality_history) {
rclcpp::QoS a(10);
rclcpp::QoS b(10);
Expand Down Expand Up @@ -75,3 +77,125 @@ TEST(TestQoS, equality_namespace) {
a.avoid_ros_namespace_conventions(true);
EXPECT_NE(a, b);
}

TEST(TestQoS, setters) {
rclcpp::QoS qos(10);

qos.keep_all();
EXPECT_EQ(RMW_QOS_POLICY_HISTORY_KEEP_ALL, qos.get_rmw_qos_profile().history);

qos.keep_last(20);
EXPECT_EQ(RMW_QOS_POLICY_HISTORY_KEEP_LAST, qos.get_rmw_qos_profile().history);
EXPECT_EQ(20u, qos.get_rmw_qos_profile().depth);

qos.reliable();
EXPECT_EQ(RMW_QOS_POLICY_RELIABILITY_RELIABLE, qos.get_rmw_qos_profile().reliability);

qos.durability_volatile();
EXPECT_EQ(RMW_QOS_POLICY_DURABILITY_VOLATILE, qos.get_rmw_qos_profile().durability);

qos.transient_local();
EXPECT_EQ(RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL, qos.get_rmw_qos_profile().durability);

qos.history(RMW_QOS_POLICY_HISTORY_KEEP_ALL);
EXPECT_EQ(RMW_QOS_POLICY_HISTORY_KEEP_ALL, qos.get_rmw_qos_profile().history);

constexpr size_t duration_ns = 12345;
constexpr std::chrono::nanoseconds duration(duration_ns);
qos.deadline(duration);
EXPECT_EQ(0u, qos.get_rmw_qos_profile().deadline.sec);
EXPECT_EQ(duration_ns, qos.get_rmw_qos_profile().deadline.nsec);

const rmw_time_t rmw_time {0, 54321};
qos.deadline(rmw_time);
EXPECT_EQ(rmw_time.sec, qos.get_rmw_qos_profile().deadline.sec);
EXPECT_EQ(rmw_time.nsec, qos.get_rmw_qos_profile().deadline.nsec);

qos.lifespan(duration);
EXPECT_EQ(0u, qos.get_rmw_qos_profile().lifespan.sec);
EXPECT_EQ(duration_ns, qos.get_rmw_qos_profile().lifespan.nsec);

qos.lifespan(rmw_time);
EXPECT_EQ(rmw_time.sec, qos.get_rmw_qos_profile().lifespan.sec);
EXPECT_EQ(rmw_time.nsec, qos.get_rmw_qos_profile().lifespan.nsec);

qos.liveliness(RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC);
EXPECT_EQ(RMW_QOS_POLICY_LIVELINESS_MANUAL_BY_TOPIC, qos.get_rmw_qos_profile().liveliness);

qos.liveliness_lease_duration(duration);
EXPECT_EQ(0u, qos.get_rmw_qos_profile().liveliness_lease_duration.sec);
EXPECT_EQ(duration_ns, qos.get_rmw_qos_profile().liveliness_lease_duration.nsec);

qos.liveliness_lease_duration(rmw_time);
EXPECT_EQ(rmw_time.sec, qos.get_rmw_qos_profile().liveliness_lease_duration.sec);
EXPECT_EQ(rmw_time.nsec, qos.get_rmw_qos_profile().liveliness_lease_duration.nsec);

qos.avoid_ros_namespace_conventions(true);
EXPECT_TRUE(qos.get_rmw_qos_profile().avoid_ros_namespace_conventions);
qos.avoid_ros_namespace_conventions(false);
EXPECT_FALSE(qos.get_rmw_qos_profile().avoid_ros_namespace_conventions);
}

bool operator==(const rmw_qos_profile_t & lhs, const rmw_qos_profile_t & rhs)
{
if (lhs.history != rhs.history) {
return false;
}
switch (lhs.history) {
case RMW_QOS_POLICY_HISTORY_KEEP_ALL:
return true;
case RMW_QOS_POLICY_HISTORY_KEEP_LAST:
case RMW_QOS_POLICY_HISTORY_SYSTEM_DEFAULT:
case RMW_QOS_POLICY_HISTORY_UNKNOWN:
return lhs.depth == rhs.depth;
}
throw std::runtime_error("This line shouldn't be reached");
}

TEST(TestQoS, DerivedTypes) {
rclcpp::SensorDataQoS sensor_data_qos;
EXPECT_EQ(rmw_qos_profile_sensor_data, sensor_data_qos.get_rmw_qos_profile());

rclcpp::ParametersQoS parameter_qos;
EXPECT_EQ(rmw_qos_profile_parameters, parameter_qos.get_rmw_qos_profile());

rclcpp::ServicesQoS services_qos;
EXPECT_EQ(rmw_qos_profile_services_default, services_qos.get_rmw_qos_profile());

rclcpp::ParameterEventsQoS parameter_events_qos;
EXPECT_EQ(rmw_qos_profile_parameter_events, parameter_events_qos.get_rmw_qos_profile());

rclcpp::RosoutQoS rosout_qos;
EXPECT_EQ(rcl_qos_profile_rosout_default, rosout_qos.get_rmw_qos_profile());

rclcpp::SystemDefaultsQoS system_default_qos;
const rclcpp::KeepLast expected_initialization(RMW_QOS_POLICY_DEPTH_SYSTEM_DEFAULT);
const rclcpp::QoS expected_default(expected_initialization);
EXPECT_EQ(expected_default.get_rmw_qos_profile(), system_default_qos.get_rmw_qos_profile());
}

TEST(TestQoS, policy_name_from_kind) {
EXPECT_EQ(
"DURABILITY_QOS_POLICY",
rclcpp::qos_policy_name_from_kind(RMW_QOS_POLICY_DURABILITY));

EXPECT_EQ(
"DEADLINE_QOS_POLICY",
rclcpp::qos_policy_name_from_kind(RMW_QOS_POLICY_DEADLINE));

EXPECT_EQ(
"LIVELINESS_QOS_POLICY",
rclcpp::qos_policy_name_from_kind(RMW_QOS_POLICY_LIVELINESS));

EXPECT_EQ(
"RELIABILITY_QOS_POLICY",
rclcpp::qos_policy_name_from_kind(RMW_QOS_POLICY_RELIABILITY));

EXPECT_EQ(
"HISTORY_QOS_POLICY",
rclcpp::qos_policy_name_from_kind(RMW_QOS_POLICY_HISTORY));

EXPECT_EQ(
"LIFESPAN_QOS_POLICY",
rclcpp::qos_policy_name_from_kind(RMW_QOS_POLICY_LIFESPAN));
}
105 changes: 103 additions & 2 deletions rclcpp/test/rclcpp/test_qos_event.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@
#include "rmw/rmw.h"
#include "test_msgs/msg/empty.hpp"

#include "../mocking_utils/patch.hpp"

class TestQosEvent : public ::testing::Test
{
protected:
Expand Down Expand Up @@ -207,9 +209,14 @@ TEST_F(TestQosEvent, test_default_incompatible_qos_callbacks)
rclcpp::executors::SingleThreadedExecutor ex;
ex.add_node(node->get_node_base_interface());

ex.spin_until_future_complete(log_msgs_future, std::chrono::seconds(10));
// This future won't complete on fastrtps, so just timeout immediately
const auto timeout = (is_fastrtps) ? std::chrono::milliseconds(5) : std::chrono::seconds(10);
ex.spin_until_future_complete(log_msgs_future, timeout);

if (!is_fastrtps) {
if (is_fastrtps) {
EXPECT_EQ("", pub_log_msg);
EXPECT_EQ("", sub_log_msg);
} else {
EXPECT_EQ(
"New subscription discovered on this topic, requesting incompatible QoS. "
"No messages will be sent to it. Last incompatible policy: DURABILITY_QOS_POLICY",
Expand All @@ -222,3 +229,97 @@ TEST_F(TestQosEvent, test_default_incompatible_qos_callbacks)

rcutils_logging_set_output_handler(original_output_handler);
}

TEST_F(TestQosEvent, construct_destruct_rcl_error) {
auto publisher = node->create_publisher<test_msgs::msg::Empty>(topic_name, 10);
auto rcl_handle = publisher->get_publisher_handle();
ASSERT_NE(nullptr, rcl_handle);

// This callback requires some type of parameter, but it could be anything
auto callback = [](int) {};
const rcl_publisher_event_type_t event_type = RCL_PUBLISHER_OFFERED_DEADLINE_MISSED;

{
// Logs error and returns
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_publisher_event_init, RCL_RET_ERROR);

auto throwing_statement = [callback, rcl_handle, event_type]() {
// reset() is not needed for the exception, but it handles unused return value warning
std::make_shared<
rclcpp::QOSEventHandler<decltype(callback), std::shared_ptr<rcl_publisher_t>>>(
callback, rcl_publisher_event_init, rcl_handle, event_type).reset();
};
// This is done through a lambda because the compiler is having trouble parsing the templated
// function inside a macro.
EXPECT_THROW(throwing_statement(), rclcpp::exceptions::RCLError);
}

{
// Logs error and returns
auto mock = mocking_utils::inject_on_return(
"lib:rclcpp", rcl_event_fini, RCL_RET_ERROR);

auto throwing_statement = [callback, rcl_handle, event_type]() {
// reset() is needed for this exception
std::make_shared<
rclcpp::QOSEventHandler<decltype(callback), std::shared_ptr<rcl_publisher_t>>>(
callback, rcl_publisher_event_init, rcl_handle, event_type).reset();
};

// This is done through a lambda because the compiler is having trouble parsing the templated
// function inside a macro.
EXPECT_NO_THROW(throwing_statement());
}
}

TEST_F(TestQosEvent, execute) {
auto publisher = node->create_publisher<test_msgs::msg::Empty>(topic_name, 10);
auto rcl_handle = publisher->get_publisher_handle();

bool handler_callback_executed = false;
// This callback requires some type of parameter, but it could be anything
auto callback = [&handler_callback_executed](int) {handler_callback_executed = true;};
rcl_publisher_event_type_t event_type = RCL_PUBLISHER_OFFERED_DEADLINE_MISSED;

rclcpp::QOSEventHandler<decltype(callback), decltype(rcl_handle)> handler(
callback, rcl_publisher_event_init, rcl_handle, event_type);

EXPECT_NO_THROW(handler.execute());
EXPECT_TRUE(handler_callback_executed);

{
handler_callback_executed = false;
// Logs error and returns early
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_take_event, RCL_RET_ERROR);
EXPECT_NO_THROW(handler.execute());
EXPECT_FALSE(handler_callback_executed);
}
}

TEST_F(TestQosEvent, add_to_wait_set) {
auto publisher = node->create_publisher<test_msgs::msg::Empty>(topic_name, 10);
auto rcl_handle = publisher->get_publisher_handle();

// This callback requires some type of parameter, but it could be anything
auto callback = [](int) {};

rcl_publisher_event_type_t event_type = RCL_PUBLISHER_OFFERED_DEADLINE_MISSED;
rclcpp::QOSEventHandler<decltype(callback), decltype(rcl_handle)> handler(
callback, rcl_publisher_event_init, rcl_handle, event_type);

EXPECT_EQ(1u, handler.get_number_of_ready_events());

{
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
auto mock = mocking_utils::patch_and_return("lib:rclcpp", rcl_wait_set_add_event, RCL_RET_OK);
EXPECT_TRUE(handler.add_to_wait_set(&wait_set));
}

{
rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
auto mock = mocking_utils::patch_and_return(
"lib:rclcpp", rcl_wait_set_add_event, RCL_RET_ERROR);
EXPECT_THROW(handler.add_to_wait_set(&wait_set), rclcpp::exceptions::RCLError);
}
}

0 comments on commit 9e0c964

Please sign in to comment.