|
|
|
@ -1593,7 +1593,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
@@ -1593,7 +1593,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
|
|
|
|
|
configure_stream_local("EXTENDED_SYS_STATE", 1.0f); |
|
|
|
|
configure_stream_local("GLOBAL_POSITION_INT", 5.0f); |
|
|
|
|
configure_stream_local("GIMBAL_DEVICE_ATTITUDE_STATUS", 1.0f); |
|
|
|
|
configure_stream_local("GIMBAL_MANAGER_STATUS", 5.0f); |
|
|
|
|
configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f); |
|
|
|
|
configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 5.0f); |
|
|
|
|
configure_stream_local("GPS2_RAW", 1.0f); |
|
|
|
|
configure_stream_local("GPS_RAW_INT", 1.0f); |
|
|
|
@ -1651,7 +1651,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
@@ -1651,7 +1651,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
|
|
|
|
|
configure_stream_local("ESTIMATOR_STATUS", 1.0f); |
|
|
|
|
configure_stream_local("EXTENDED_SYS_STATE", 5.0f); |
|
|
|
|
configure_stream_local("GIMBAL_DEVICE_ATTITUDE_STATUS", 1.0f); |
|
|
|
|
configure_stream_local("GIMBAL_MANAGER_STATUS", 5.0f); |
|
|
|
|
configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f); |
|
|
|
|
configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 5.0f); |
|
|
|
|
configure_stream_local("GLOBAL_POSITION_INT", 50.0f); |
|
|
|
|
configure_stream_local("GPS2_RAW", unlimited_rate); |
|
|
|
|