From b5576dda4ffbe139d87b30576e14e2f0b219ee38 Mon Sep 17 00:00:00 2001 From: Kristoffer Bergman Date: Wed, 24 May 2023 09:17:37 +0200 Subject: [PATCH] Use SensorDataQoS for gp_origin subscriber --- mavros_extras/src/plugins/guided_target.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/mavros_extras/src/plugins/guided_target.cpp b/mavros_extras/src/plugins/guided_target.cpp index e050b84d3..d56099512 100644 --- a/mavros_extras/src/plugins/guided_target.cpp +++ b/mavros_extras/src/plugins/guided_target.cpp @@ -67,7 +67,7 @@ class GuidedTargetPlugin : public plugin::Plugin // Subscriber for global origin (aka map origin). gp_origin_sub = node->create_subscription( - "global_position/gp_origin", 10, std::bind(&GuidedTargetPlugin::gp_origin_cb, this, _1)); + "global_position/gp_origin", rclcpp::SensorDataQoS(), std::bind(&GuidedTargetPlugin::gp_origin_cb, this, _1)); } Subscriptions get_subscriptions() override