Skip to content

Commit

Permalink
Change odometry subscription queue to 1 to avoid buffering.
Browse files Browse the repository at this point in the history
  • Loading branch information
jgoppert authored and mhkabir committed Dec 13, 2019
1 parent e2cd26e commit 63183a6
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion mavros_extras/src/plugins/odom.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ class OdometryPlugin : public plugin::PluginBase {
odom_pub = odom_nh.advertise<nav_msgs::Odometry>("in", 10);

// subscribers
odom_sub = odom_nh.subscribe("out", 10, &OdometryPlugin::odom_cb, this);
odom_sub = odom_nh.subscribe("out", 1, &OdometryPlugin::odom_cb, this);
}

Subscriptions get_subscriptions()
Expand Down

0 comments on commit 63183a6

Please sign in to comment.