mavlink: Crank up param transmission rate

This commit is contained in:
Lorenz Meier
2015-03-28 13:54:19 -07:00
parent 8ebf9755e4
commit a184aebf0f
+1 -1
View File
@@ -1361,7 +1361,7 @@ Mavlink::task_main(int argc, char *argv[])
/* PARAM_VALUE stream */
_parameters_manager = (MavlinkParametersManager *) MavlinkParametersManager::new_instance(this);
_parameters_manager->set_interval(interval_from_rate(80.0f));
_parameters_manager->set_interval(interval_from_rate(120.0f));
LL_APPEND(_streams, _parameters_manager);
/* MISSION_STREAM stream, actually sends all MISSION_XXX messages at some rate depending on