forked from Archive/PX4-Autopilot
mavlink streams: add SYSTEM_TIME to onboard low bandwidth
It's required with 2Hz by some MAVLink enabled payloads.
This commit is contained in:
parent
9184a8f4ef
commit
d8d2213cab
|
@ -1756,6 +1756,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
|
|||
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("SYSTEM_TIME", 2.0f);
|
||||
configure_stream_local("TIME_ESTIMATE_TO_TARGET", 1.0f);
|
||||
configure_stream_local("TRAJECTORY_REPRESENTATION_WAYPOINTS", 5.0f);
|
||||
configure_stream_local("UTM_GLOBAL_POSITION", 1.0f);
|
||||
|
|
Loading…
Reference in New Issue