mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-25 00:31:36 +08:00
mavlink: Crank up param transmission rate
This commit is contained in:
@@ -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
|
||||
|
||||
Reference in New Issue
Block a user