modules: mavlink: only include FUEL_STATUS stream if the dialect includes it

This commit is contained in:
Nuno Marques
2024-05-15 17:01:51 +01:00
parent a8cb5a7715
commit 450ae033e4
2 changed files with 18 additions and 6 deletions
+15 -5
View File
@@ -1413,7 +1413,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("ESC_STATUS", 1.0f);
configure_stream_local("ESTIMATOR_STATUS", 0.5f);
configure_stream_local("EXTENDED_SYS_STATE", 1.0f);
configure_stream_local("FUEL_STATUS", 1.0f);
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);
@@ -1453,6 +1452,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
#if defined(MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS)
configure_stream_local("FIGURE_EIGHT_EXECUTION_STATUS", 5.0f);
#endif // MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS
#if defined(MAVLINK_MSG_ID_FUEL_STATUS)
configure_stream_local("FUEL_STATUS", 1.0f);
#endif // MAVLINK_MSG_ID_FUEL_STATUS
#endif // !CONSTRAINED_FLASH
break;
@@ -1483,7 +1485,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("EFI_STATUS", 2.0f);
configure_stream_local("ESTIMATOR_STATUS", 1.0f);
configure_stream_local("EXTENDED_SYS_STATE", 5.0f);
configure_stream_local("FUEL_STATUS", 1.0f);
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);
@@ -1523,6 +1524,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
#if defined(MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS)
configure_stream_local("FIGURE_EIGHT_EXECUTION_STATUS", 5.0f);
#endif // MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS
#if defined(MAVLINK_MSG_ID_FUEL_STATUS)
configure_stream_local("FUEL_STATUS", 1.0f);
#endif // MAVLINK_MSG_ID_FUEL_STATUS
#endif // !CONSTRAINED_FLASH
break;
@@ -1558,7 +1562,6 @@ 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);
configure_stream_local("FUEL_STATUS", 1.0f);
configure_stream_local("GLOBAL_POSITION_INT", 5.0f);
configure_stream_local("GPS2_RAW", 1.0f);
configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f);
@@ -1589,6 +1592,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
#if defined(MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS)
configure_stream_local("FIGURE_EIGHT_EXECUTION_STATUS", 2.0f);
#endif // MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS
#if defined(MAVLINK_MSG_ID_FUEL_STATUS)
configure_stream_local("FUEL_STATUS", 1.0f);
#endif // MAVLINK_MSG_ID_FUEL_STATUS
#endif // !CONSTRAINED_FLASH
break;
@@ -1645,7 +1651,6 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
configure_stream_local("ESC_STATUS", 10.0f);
configure_stream_local("ESTIMATOR_STATUS", 5.0f);
configure_stream_local("EXTENDED_SYS_STATE", 2.0f);
configure_stream_local("FUEL_STATUS", 2.0f);
configure_stream_local("GLOBAL_POSITION_INT", 10.0f);
configure_stream_local("GPS2_RAW", unlimited_rate);
configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f);
@@ -1690,6 +1695,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
#if defined(MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS)
configure_stream_local("FIGURE_EIGHT_EXECUTION_STATUS", 5.0f);
#endif // MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS
#if defined(MAVLINK_MSG_ID_FUEL_STATUS)
configure_stream_local("FUEL_STATUS", 2.0f);
#endif // MAVLINK_MSG_ID_FUEL_STATUS
#endif // !CONSTRAINED_FLASH
break;
@@ -1742,7 +1750,6 @@ 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);
configure_stream_local("FUEL_STATUS", 1.0f);
configure_stream_local("GLOBAL_POSITION_INT", 10.0f);
configure_stream_local("GPS_GLOBAL_ORIGIN", 1.0f);
configure_stream_local("GPS2_RAW", unlimited_rate);
@@ -1774,6 +1781,9 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
#if defined(MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS)
configure_stream_local("FIGURE_EIGHT_EXECUTION_STATUS", 5.0f);
#endif // MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS
#if defined(MAVLINK_MSG_ID_FUEL_STATUS)
configure_stream_local("FUEL_STATUS", 1.0f);
#endif // MAVLINK_MSG_ID_FUEL_STATUS
#endif // !CONSTRAINED_FLASH
break;
+3 -1
View File
@@ -75,7 +75,6 @@
#include "streams/ESC_STATUS.hpp"
#include "streams/ESTIMATOR_STATUS.hpp"
#include "streams/EXTENDED_SYS_STATE.hpp"
#include "streams/FUEL_STATUS.hpp"
#include "streams/FLIGHT_INFORMATION.hpp"
#include "streams/GLOBAL_POSITION_INT.hpp"
#include "streams/GPS_GLOBAL_ORIGIN.hpp"
@@ -124,6 +123,9 @@
#if defined(MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS)
#include "streams/FIGURE_EIGHT_EXECUTION_STATUS.hpp"
#endif // MAVLINK_MSG_ID_FIGURE_EIGHT_EXECUTION_STATUS
#if defined(MAVLINK_MSG_ID_FUEL_STATUS)
#include "streams/FUEL_STATUS.hpp"
#endif // MAVLINK_MSG_ID_FUEL_STATUS
#ifdef MAVLINK_MSG_ID_AVAILABLE_MODES // Only defined if development.xml is used
#include "streams/AVAILABLE_MODES.hpp"