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

move qos_profile_rosout_default to rmw. #1195

Open
wants to merge 1 commit into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
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
19 changes: 0 additions & 19 deletions rcl/include/rcl/logging_rosout.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,25 +28,6 @@ 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 =
Copy link
Collaborator Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this is the only profile managed by rcl. this can be moved to rmw with other preset profiles.

{
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
4 changes: 3 additions & 1 deletion rcl/src/rcl/node_options.c
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,8 @@ extern "C"
#include "rcl/error_handling.h"
#include "rcl/logging_rosout.h"

#include "rmw/qos_profiles.h"

rcl_node_options_t
rcl_node_get_default_options(void)
{
Expand All @@ -35,7 +37,7 @@ rcl_node_get_default_options(void)
.use_global_arguments = true,
.arguments = rcl_get_zero_initialized_arguments(),
.enable_rosout = true,
.rosout_qos = rcl_qos_profile_rosout_default,
.rosout_qos = rmw_qos_profile_rosout_default,
};
return default_options;
}
Expand Down
2 changes: 1 addition & 1 deletion rcl/test/rcl/test_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -859,7 +859,7 @@ TEST_F(TestNodeFixture, test_rcl_node_options) {

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_EQ(rmw_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 Down