Skip to content

Commit

Permalink
Make reliable explicit on the QoS
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Jan 20, 2025
1 parent 7952d89 commit 27af6fe
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -295,7 +295,7 @@ void ControllerManager::init_controller_manager()
{
controller_manager_activity_publisher_ =
create_publisher<controller_manager_msgs::msg::ControllerManagerActivity>(
"~/activity", rclcpp::QoS(1).transient_local());
"~/activity", rclcpp::QoS(1).reliable().transient_local());
rt_controllers_wrapper_.set_on_switch_callback(
std::bind(&ControllerManager::publish_activity, this));
resource_manager_->set_on_component_state_switch_callback(
Expand Down
2 changes: 1 addition & 1 deletion controller_manager/test/test_controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ class TestControllerManagerWithStrictness
{ received_msg = msg; };
auto subscription =
test_node.create_subscription<controller_manager_msgs::msg::ControllerManagerActivity>(
topic, rclcpp::QoS(1).transient_local(), subs_callback);
topic, rclcpp::QoS(1).reliable().transient_local(), subs_callback);

rclcpp::executors::SingleThreadedExecutor executor;
executor.add_node(test_node.get_node_base_interface());
Expand Down

0 comments on commit 27af6fe

Please sign in to comment.