Skip to content

Commit eb6ec49

Browse files
committed
feat: use keep_all on input messages to bridge
Signed-off-by: Bart Jimenez Vera <bjv@capra.ooo>
1 parent e055229 commit eb6ec49

1 file changed

Lines changed: 6 additions & 4 deletions

File tree

micro_ros_diagnostic_bridge/src/micro_ros_diagnostic_bridge/micro_ros_diagnostic_bridge.cpp

Lines changed: 6 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -43,12 +43,12 @@ MicroROSDiagnosticBridge::MicroROSDiagnosticBridge(const std::string & path)
4343
}
4444
read_lookup_table(lookup_table_path);
4545

46-
rclcpp::QoS qos{rclcpp::KeepLast{10}};
47-
qos.reliable();
46+
rclcpp::QoS qos_out{rclcpp::KeepLast{10}};
47+
qos_out.reliable();
4848

4949
ros2_diagnostics_pub_ = create_publisher<DiagnosticArray>(
5050
UROS_DIAGNOSTICS_BRIDGE_TOPIC_OUT,
51-
qos);
51+
qos_out);
5252

5353
auto callback =
5454
[this](const MicroROSDiagnosticStatus::SharedPtr msg_in) -> void
@@ -97,9 +97,11 @@ MicroROSDiagnosticBridge::MicroROSDiagnosticBridge(const std::string & path)
9797
ros2_diagnostics_pub_->publish(std::move(msg_out));
9898
};
9999

100+
rclcpp::QoS qos_in{rclcpp::KeepAll{}};
101+
qos_in.reliable();
100102
uros_diagnostics_sub_ = create_subscription<MicroROSDiagnosticStatus>(
101103
UROS_DIAGNOSTICS_BRIDGE_TOPIC_IN,
102-
qos,
104+
qos_in,
103105
callback);
104106
}
105107

0 commit comments

Comments
 (0)