Skip to content

Commit 4b8ca5f

Browse files
committed
Expose qos setting for /rosout
Signed-off-by: Ada-King <[email protected]>
1 parent 2a4d2f4 commit 4b8ca5f

File tree

4 files changed

+28
-6
lines changed

4 files changed

+28
-6
lines changed

rcl/include/rcl/logging_rosout.h

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,19 @@ extern "C"
2626
{
2727
#endif
2828

29+
static const rmw_qos_profile_t rmw_qos_profile_rosout_default =
30+
{
31+
RMW_QOS_POLICY_HISTORY_KEEP_LAST,
32+
1000,
33+
RMW_QOS_POLICY_RELIABILITY_RELIABLE,
34+
RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL,
35+
RMW_QOS_DEADLINE_DEFAULT,
36+
{10, 0},
37+
RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
38+
RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT,
39+
false
40+
};
41+
2942
/// Initializes the rcl_logging_rosout features
3043
/**
3144
* Calling this will initialize the rcl_logging_rosout features. This function must be called

rcl/include/rcl/node_options.h

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,9 @@ extern "C"
2525

2626
#include "rcl/domain_id.h"
2727

28+
#include "rcl/logging_rosout.h"
29+
#include "rmw/qos_profiles.h"
30+
2831
/// Constant which indicates that the default domain id should be used.
2932
#define RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID RCL_DEFAULT_DOMAIN_ID
3033

@@ -49,6 +52,9 @@ typedef struct rcl_node_options_t
4952

5053
/// Flag to enable rosout for this node
5154
bool enable_rosout;
55+
56+
/// Middleware quality of service settings for /rosout.
57+
rmw_qos_profile_t rosout_qos;
5258
} rcl_node_options_t;
5359

5460
/// Return the default node options in a rcl_node_options_t.

rcl/src/rcl/logging_rosout.c

Lines changed: 6 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -173,11 +173,12 @@ rcl_ret_t rcl_logging_rosout_init_publisher_for_node(
173173
const rosidl_message_type_support_t * type_support =
174174
rosidl_typesupport_c__get_message_type_support_handle__rcl_interfaces__msg__Log();
175175
rcl_publisher_options_t options = rcl_publisher_get_default_options();
176-
// Late joining subscriptions get the last 10 seconds of logs, up to 1000 logs.
177-
options.qos.depth = 1000;
178-
options.qos.durability = RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL;
179-
options.qos.lifespan.sec = 10;
180-
options.qos.lifespan.nsec = 0;
176+
177+
// Late joining subscriptions get the user's setting of rosout qos options.
178+
const rcl_node_options_t *node_options = rcl_node_get_options(node);
179+
RCL_CHECK_FOR_NULL_WITH_MSG(node_options, "Node options was null.", return RCL_RET_ERROR);
180+
181+
options.qos = node_options->rosout_qos;
181182
new_entry.publisher = rcl_get_zero_initialized_publisher();
182183
status =
183184
rcl_publisher_init(&new_entry.publisher, node, type_support, ROSOUT_TOPIC_NAME, &options);

rcl/src/rcl/node_options.c

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -28,9 +28,10 @@ rcl_node_options_t
2828
rcl_node_get_default_options()
2929
{
3030
// !!! MAKE SURE THAT CHANGES TO THESE DEFAULTS ARE REFLECTED IN THE HEADER DOC STRING
31-
static rcl_node_options_t default_options = {
31+
rcl_node_options_t default_options = {
3232
.use_global_arguments = true,
3333
.enable_rosout = true,
34+
.rosout_qos = rmw_qos_profile_rosout_default,
3435
};
3536
// Must set the allocator after because it is not a compile time constant.
3637
default_options.allocator = rcl_get_default_allocator();
@@ -56,6 +57,7 @@ rcl_node_options_copy(
5657
options_out->allocator = options->allocator;
5758
options_out->use_global_arguments = options->use_global_arguments;
5859
options_out->enable_rosout = options->enable_rosout;
60+
options_out->rosout_qos = options->rosout_qos;
5961
if (NULL != options->arguments.impl) {
6062
rcl_ret_t ret = rcl_arguments_copy(&(options->arguments), &(options_out->arguments));
6163
return ret;

0 commit comments

Comments
 (0)