Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Expose qos setting for /rosout #722

Merged
merged 4 commits into from
Aug 4, 2020
Merged
Changes from 1 commit
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
27 changes: 27 additions & 0 deletions rcl/test/rcl/test_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include "osrf_testing_tools_cpp/memory_tools/memory_tools.hpp"
#include "osrf_testing_tools_cpp/scope_exit.hpp"
#include "rcl/error_handling.h"
#include "rcl/logging_rosout.h"

#ifdef RMW_IMPLEMENTATION
# define CLASSNAME_(NAME, SUFFIX) NAME ## __ ## SUFFIX
Expand All @@ -39,6 +40,28 @@ using osrf_testing_tools_cpp::memory_tools::on_unexpected_realloc;
using osrf_testing_tools_cpp::memory_tools::on_unexpected_calloc;
using osrf_testing_tools_cpp::memory_tools::on_unexpected_free;

bool operator==(
const rmw_time_t & lhs,
const rmw_time_t & rhs)
{
return lhs.sec == rhs.sec && lhs.nsec == rhs.nsec;
}

bool operator==(
const rmw_qos_profile_t & lhs,
const rmw_qos_profile_t & rhs)
{
return lhs.history == rhs.history &&
lhs.depth == rhs.depth &&
lhs.reliability == rhs.reliability &&
lhs.durability == rhs.durability &&
lhs.deadline == rhs.deadline &&
lhs.lifespan == rhs.lifespan &&
lhs.liveliness == rhs.liveliness &&
lhs.liveliness_lease_duration == rhs.liveliness_lease_duration &&
lhs.avoid_ros_namespace_conventions == rhs.avoid_ros_namespace_conventions;
}

class CLASSNAME (TestNodeFixture, RMW_IMPLEMENTATION) : public ::testing::Test
{
public:
Expand Down Expand Up @@ -723,11 +746,13 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_names) {
TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_options) {
rcl_node_options_t default_options = rcl_node_get_default_options();
rcl_node_options_t not_ini_options = rcl_node_get_default_options();
memset(&not_ini_options.rosout_qos, 0, sizeof(rmw_qos_profile_t));

EXPECT_TRUE(default_options.use_global_arguments);
EXPECT_TRUE(default_options.enable_rosout);
EXPECT_TRUE(rcutils_allocator_is_valid(&(default_options.allocator)));

EXPECT_EQ(rcl_qos_profile_rosout_default, default_options.rosout_qos);
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_node_options_copy(nullptr, &default_options));
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_node_options_copy(&default_options, nullptr));
EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_node_options_copy(&default_options, &default_options));
Expand All @@ -740,9 +765,11 @@ TEST_F(CLASSNAME(TestNodeFixture, RMW_IMPLEMENTATION), test_rcl_node_options) {
rcl_parse_arguments(argc, argv, default_options.allocator, &(default_options.arguments)));
default_options.use_global_arguments = false;
default_options.enable_rosout = false;
default_options.rosout_qos = rcl_qos_profile_rosout_default;
ivanpauno marked this conversation as resolved.
Show resolved Hide resolved
EXPECT_EQ(RCL_RET_OK, rcl_node_options_copy(&default_options, &not_ini_options));
EXPECT_FALSE(not_ini_options.use_global_arguments);
EXPECT_FALSE(not_ini_options.enable_rosout);
EXPECT_EQ(rcl_qos_profile_rosout_default, not_ini_options.rosout_qos);
EXPECT_EQ(
rcl_arguments_get_count_unparsed(&(default_options.arguments)),
rcl_arguments_get_count_unparsed(&(not_ini_options.arguments)));
Expand Down