mavlink streams: increase RC_CHANNELS rate for onboard low bandwidth

There are MAVLink enabled gimbals that directly consume RC channel data.
The gimbal controls stutter with this profile when the rate is too low.
This commit is contained in:
Matthias Grob 2023-12-01 11:53:29 +01:00 committed by Daniel Agar
parent 938be68c69
commit 3ceb932b7c
1 changed files with 1 additions and 1 deletions

View File

@ -1752,7 +1752,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("PING", 0.1f);
configure_stream_local("POSITION_TARGET_GLOBAL_INT", 1.5f);
configure_stream_local("POSITION_TARGET_LOCAL_NED", 1.5f);
configure_stream_local("RC_CHANNELS", 5.0f);
configure_stream_local("RC_CHANNELS", 20.0f);
configure_stream_local("SERVO_OUTPUT_RAW_0", 1.0f);
configure_stream_local("SYS_STATUS", 5.0f);
configure_stream_local("TIME_ESTIMATE_TO_TARGET", 1.0f);