Skip to content

Commit

Permalink
Expose qos setting for /rosout
Browse files Browse the repository at this point in the history
Signed-off-by: Ada-King <Bingtao.Du@sony.com>
  • Loading branch information
Ada-King committed Jul 27, 2020
1 parent 2a4d2f4 commit 7b779c0
Show file tree
Hide file tree
Showing 4 changed files with 25 additions and 6 deletions.
13 changes: 13 additions & 0 deletions rcl/include/rcl/logging_rosout.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,19 @@ extern "C"
{
#endif

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
3 changes: 3 additions & 0 deletions rcl/include/rcl/node_options.h
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,9 @@ 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.
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
4 changes: 3 additions & 1 deletion rcl/src/rcl/node_options.c
Original file line number Diff line number Diff line change
Expand Up @@ -28,9 +28,10 @@ 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 = {
.use_global_arguments = true,
.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();
Expand All @@ -56,6 +57,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

0 comments on commit 7b779c0

Please sign in to comment.