Skip to content

Commit

Permalink
Expose qos setting for /rosout (ros2#722)
Browse files Browse the repository at this point in the history
* Expose qos setting for /rosout

Signed-off-by: Ada-King <[email protected]>

* Modify some details based on review

Signed-off-by: Ada-King <[email protected]>

* Add test

Signed-off-by: Ada-King <[email protected]>

* Modify based on reviews

Signed-off-by: Ada-King <[email protected]>
  • Loading branch information
Ada-King authored Aug 4, 2020
1 parent af438bc commit b0d0143
Show file tree
Hide file tree
Showing 5 changed files with 61 additions and 10 deletions.
19 changes: 19 additions & 0 deletions rcl/include/rcl/logging_rosout.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,25 @@ extern "C"
{
#endif

/// The default qos profile setting for topic /rosout
/**
* - depth = 1000
* - durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL
* - lifespan = {10, 0}
*/
static const rmw_qos_profile_t rcl_qos_profile_rosout_default =
{
RMW_QOS_POLICY_HISTORY_KEEP_LAST,
1000,
RMW_QOS_POLICY_RELIABILITY_RELIABLE,
RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL,
RMW_QOS_DEADLINE_DEFAULT,
{10, 0},
RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT,
false
};

/// Initializes the rcl_logging_rosout features
/**
* Calling this will initialize the rcl_logging_rosout features. This function must be called
Expand Down
5 changes: 4 additions & 1 deletion rcl/include/rcl/node_options.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,17 +49,20 @@ typedef struct rcl_node_options_t

/// Flag to enable rosout for this node
bool enable_rosout;

/// Middleware quality of service settings for /rosout.
rmw_qos_profile_t rosout_qos;
} rcl_node_options_t;

/// Return the default node options in a rcl_node_options_t.
/**
* The default values are:
*
* - domain_id = RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID
* - allocator = rcl_get_default_allocator()
* - use_global_arguments = true
* - enable_rosout = true
* - arguments = rcl_get_zero_initialized_arguments()
* - rosout_qos = rcl_qos_profile_rosout_default
*/
RCL_PUBLIC
rcl_node_options_t
Expand Down
11 changes: 6 additions & 5 deletions rcl/src/rcl/logging_rosout.c
Original file line number Diff line number Diff line change
Expand Up @@ -173,11 +173,12 @@ rcl_ret_t rcl_logging_rosout_init_publisher_for_node(
const rosidl_message_type_support_t * type_support =
rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__Log();
rcl_publisher_options_t options = rcl_publisher_get_default_options();
// Late joining subscriptions get the last 10 seconds of logs, up to 1000 logs.
options.qos.depth = 1000;
options.qos.durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
options.qos.lifespan.sec = 10;
options.qos.lifespan.nsec = 0;

// Late joining subscriptions get the user's setting of rosout qos options.
const rcl_node_options_t * node_options = rcl_node_get_options(node);
RCL_CHECK_FOR_NULL_WITH_MSG(node_options, "Node options was null.", return RCL_RET_ERROR);

options.qos = node_options->rosout_qos;
new_entry.publisher = rcl_get_zero_initialized_publisher();
status =
rcl_publisher_init(&new_entry.publisher, node, type_support, ROSOUT_TOPIC_NAME, &options);
Expand Down
9 changes: 5 additions & 4 deletions rcl/src/rcl/node_options.c
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,13 @@ rcl_node_options_t
rcl_node_get_default_options()
{
// !!! MAKE SURE THAT CHANGES TO THESE DEFAULTS ARE REFLECTED IN THE HEADER DOC STRING
static rcl_node_options_t default_options = {
rcl_node_options_t default_options = {
.allocator = rcl_get_default_allocator(),
.use_global_arguments = true,
.arguments = rcl_get_zero_initialized_arguments(),
.enable_rosout = true,
.rosout_qos = rcl_qos_profile_rosout_default,
};
// Must set the allocator after because it is not a compile time constant.
default_options.allocator = rcl_get_default_allocator();
default_options.arguments = rcl_get_zero_initialized_arguments();
return default_options;
}

Expand All @@ -56,6 +56,7 @@ rcl_node_options_copy(
options_out->allocator = options->allocator;
options_out->use_global_arguments = options->use_global_arguments;
options_out->enable_rosout = options->enable_rosout;
options_out->rosout_qos = options->rosout_qos;
if (NULL != options->arguments.impl) {
rcl_ret_t ret = rcl_arguments_copy(&(options->arguments), &(options_out->arguments));
return ret;
Expand Down
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,9 +746,11 @@ 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_EQ(rcl_qos_profile_rosout_default, default_options.rosout_qos);
EXPECT_TRUE(rcutils_allocator_is_valid(&(default_options.allocator)));

EXPECT_EQ(RCL_RET_INVALID_ARGUMENT, rcl_node_options_copy(nullptr, &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 = rmw_qos_profile_default;
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(default_options.rosout_qos, 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

0 comments on commit b0d0143

Please sign in to comment.