Skip to content

Commit

Permalink
Use SensorDataQoS for gp_origin subscriber
Browse files Browse the repository at this point in the history
  • Loading branch information
kribe48 authored and vooon committed Oct 19, 2023
1 parent 1b6c072 commit b5576dd
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion mavros_extras/src/plugins/guided_target.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ class GuidedTargetPlugin : public plugin::Plugin

// Subscriber for global origin (aka map origin).
gp_origin_sub = node->create_subscription<geographic_msgs::msg::GeoPointStamped>(
"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
Expand Down

0 comments on commit b5576dd

Please sign in to comment.