From 3cea683760b46370a118d0c45e98f3002695a800 Mon Sep 17 00:00:00 2001 From: Sem van der Hoeven Date: Mon, 22 May 2023 14:34:47 +0200 Subject: [PATCH] add qos profile sensor data --- src/drone_status/drone_status/drone_status.py | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/drone_status/drone_status/drone_status.py b/src/drone_status/drone_status/drone_status.py index db38ca2d..a3d8063b 100644 --- a/src/drone_status/drone_status/drone_status.py +++ b/src/drone_status/drone_status/drone_status.py @@ -1,5 +1,6 @@ import rclpy from rclpy.node import Node +from rclpy.qos.QoSPresetProfiles import qos_profile_sensor_data from drone_services.msg import DroneStatus from drone_services.msg import DroneControlMode @@ -26,9 +27,9 @@ class DroneStatusNode(Node): self.route_status_subscriber = self.create_subscription( DroneRouteStatus, '/drone/route_status', self.route_status_callback, 10) self.battery_status_subscriber = self.create_subscription( - BatteryStatus, '/fmu/out/battery_status', self.battery_status_callback, 10) + BatteryStatus, '/fmu/out/battery_status', self.battery_status_callback,qos_profile=qos_profile_sensor_data) self.cpu_load_subscriber = self.create_subscription( - Cpuload, '/fmu/out/cpuload', self.cpu_load_callback, 10) + Cpuload, '/fmu/out/cpuload', self.cpu_load_callback,qos_profile=qos_profile_sensor_data) # publish every 0.5 seconds self.timer = self.create_timer(0.5, self.publish_status) self.armed = False