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

use rmw_qos_profile_rosout_default instead of rcl. #2663

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
2 changes: 1 addition & 1 deletion rclcpp/include/rclcpp/qos.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -475,7 +475,7 @@ class RCLCPP_PUBLIC RosoutQoS : public QoS
explicit
RosoutQoS(
const QoSInitialization & rosout_qos_initialization = (
QoSInitialization::from_rmw(rcl_qos_profile_rosout_default)
QoSInitialization::from_rmw(rmw_qos_profile_rosout_default)
));
};

Expand Down
2 changes: 1 addition & 1 deletion rclcpp/src/rclcpp/qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -407,7 +407,7 @@ ParameterEventsQoS::ParameterEventsQoS(const QoSInitialization & qos_initializat
{}

RosoutQoS::RosoutQoS(const QoSInitialization & rosout_initialization)
: QoS(rosout_initialization, rcl_qos_profile_rosout_default)
: QoS(rosout_initialization, rmw_qos_profile_rosout_default)
{}

SystemDefaultsQoS::SystemDefaultsQoS(const QoSInitialization & qos_initialization)
Expand Down
2 changes: 1 addition & 1 deletion rclcpp/test/rclcpp/test_qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -184,7 +184,7 @@ TEST(TestQoS, DerivedTypes) {
EXPECT_EQ(rmw_qos_profile_parameter_events, parameter_events_qos.get_rmw_qos_profile());

rclcpp::RosoutQoS rosout_qos;
EXPECT_EQ(rcl_qos_profile_rosout_default, rosout_qos.get_rmw_qos_profile());
EXPECT_EQ(rmw_qos_profile_rosout_default, rosout_qos.get_rmw_qos_profile());

rclcpp::SystemDefaultsQoS system_default_qos;
const rclcpp::KeepLast expected_initialization(RMW_QOS_POLICY_DEPTH_SYSTEM_DEFAULT);
Expand Down
4 changes: 2 additions & 2 deletions rclcpp/test/rclcpp/test_rosout_qos.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -58,8 +58,8 @@ TEST(TestRosoutQoS, test_rosout_qos_with_default_value) {
rclcpp::NodeOptions node_options;
rclcpp::QoS rosout_qos_profile = node_options.rosout_qos();
rmw_qos_profile_t rmw_qos_profile = rosout_qos_profile.get_rmw_qos_profile();
EXPECT_EQ(rcl_qos_profile_rosout_default, rmw_qos_profile);
EXPECT_EQ(rcl_qos_profile_rosout_default, node_options.get_rcl_node_options()->rosout_qos);
EXPECT_EQ(rmw_qos_profile_rosout_default, rmw_qos_profile);
EXPECT_EQ(rmw_qos_profile_rosout_default, node_options.get_rcl_node_options()->rosout_qos);
}

/*
Expand Down