mavlink: GNSS_INTEGRITY and GLOBAL_POSITION are WIP (#26012)

These two messages are still work in progress, only defined in the
development.xml MAVLink dialect. Therefore, we need to ifdef them.
This commit is contained in:
Julian Oes 2025-11-28 11:41:38 +13:00 committed by GitHub
parent 4fbff2cdd9
commit 0618b0b529
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194

View File

@ -1435,9 +1435,13 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("GIMBAL_DEVICE_ATTITUDE_STATUS", 1.0f);
configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 5.0f);
configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f);
#if defined(MAVLINK_MSG_ID_GLOBAL_POSITION)
configure_stream_local("GLOBAL_POSITION", 5.0f);
#endif
configure_stream_local("GLOBAL_POSITION_INT", 5.0f);
#if defined(MAVLINK_MSG_ID_GNSS_INTEGRITY)
configure_stream_local("GNSS_INTEGRITY", 1.0f);
#endif
configure_stream_local("GPS2_RAW", 1.0f);
configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f);
configure_stream_local("GPS_RAW_INT", 5.0f);
@ -1510,7 +1514,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("GIMBAL_DEVICE_SET_ATTITUDE", 5.0f);
configure_stream_local("GIMBAL_MANAGER_STATUS", 0.5f);
configure_stream_local("GLOBAL_POSITION_INT", 50.0f);
#if defined(MAVLINK_MSG_ID_GNSS_INTEGRITY)
configure_stream_local("GNSS_INTEGRITY", 1.0f);
#endif
configure_stream_local("GPS2_RAW", unlimited_rate);
configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f);
configure_stream_local("GPS_RAW_INT", unlimited_rate);
@ -1671,7 +1677,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("ESTIMATOR_STATUS", 5.0f);
configure_stream_local("EXTENDED_SYS_STATE", 2.0f);
configure_stream_local("GLOBAL_POSITION_INT", 10.0f);
#if defined(MAVLINK_MSG_ID_GNSS_INTEGRITY)
configure_stream_local("GNSS_INTEGRITY", 1.0f);
#endif
configure_stream_local("GPS2_RAW", unlimited_rate);
configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f);
configure_stream_local("GPS_RAW_INT", unlimited_rate);
@ -1770,10 +1778,14 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("CURRENT_MODE", 0.5f);
configure_stream_local("ESTIMATOR_STATUS", 1.0f);
configure_stream_local("EXTENDED_SYS_STATE", 1.0f);
#if defined(MAVLINK_MSG_ID_GLOBAL_POSITION)
configure_stream_local("GLOBAL_POSITION", 10.0f);
#endif
configure_stream_local("GLOBAL_POSITION_INT", 10.0f);
configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f);
#if defined(MAVLINK_MSG_ID_GNSS_INTEGRITY)
configure_stream_local("GNSS_INTEGRITY", 1.0f);
#endif
configure_stream_local("GPS2_RAW", unlimited_rate);
configure_stream_local("GPS_RAW_INT", unlimited_rate);
configure_stream_local("HOME_POSITION", 0.5f);
@ -1834,7 +1846,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("ESTIMATOR_STATUS", 1.0f);
configure_stream_local("EXTENDED_SYS_STATE", 0.5f);
configure_stream_local("GLOBAL_POSITION_INT", 2.0f);
#if defined(MAVLINK_MSG_ID_GLOBAL_POSITION)
configure_stream_local("GLOBAL_POSITION", 2.0f);
#endif
configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f);
configure_stream_local("GPS2_RAW", 2.0f);
configure_stream_local("GPS_RAW_INT", 2.0f);