1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-25 01:05:27 +03:00

Allow MAVLink telemetry only for targets with >128K flash

This commit is contained in:
Konstantin Sharlaimov (DigitalEntity) 2016-10-17 18:43:28 +10:00
parent 09140cfdef
commit 8e249ce187
3 changed files with 13 additions and 1 deletions

View file

@ -55,6 +55,7 @@
#if (FLASH_SIZE > 128) #if (FLASH_SIZE > 128)
#define DISPLAY #define DISPLAY
#define TELEMETRY_MAVLINK
#else #else
#define SKIP_CLI_COMMAND_HELP #define SKIP_CLI_COMMAND_HELP
#define SKIP_RX_MSP #define SKIP_RX_MSP

View file

@ -26,7 +26,7 @@
#include "platform.h" #include "platform.h"
#if defined(TELEMETRY) #if defined(TELEMETRY) && defined(TELEMETRY_MAVLINK)
#include "common/maths.h" #include "common/maths.h"
#include "common/axis.h" #include "common/axis.h"
@ -456,6 +456,7 @@ void mavlinkSendHUDAndHeartbeat(void)
break; break;
case MIXER_FLYING_WING: case MIXER_FLYING_WING:
case MIXER_AIRPLANE: case MIXER_AIRPLANE:
case MIXER_CUSTOM_AIRPLANE:
mavSystemType = MAV_TYPE_FIXED_WING; mavSystemType = MAV_TYPE_FIXED_WING;
break; break;
case MIXER_HELI_120_CCPM: case MIXER_HELI_120_CCPM:

View file

@ -59,6 +59,10 @@ void telemetryInit(void)
initLtmTelemetry(telemetryConfig); initLtmTelemetry(telemetryConfig);
initJetiExBusTelemetry(telemetryConfig); initJetiExBusTelemetry(telemetryConfig);
#if defined(TELEMETRY_MAVLINK)
initMAVLinkTelemetry();
#endif
telemetryCheckState(); telemetryCheckState();
} }
@ -90,7 +94,10 @@ void telemetryCheckState(void)
checkSmartPortTelemetryState(); checkSmartPortTelemetryState();
checkLtmTelemetryState(); checkLtmTelemetryState();
checkJetiExBusTelemetryState(); checkJetiExBusTelemetryState();
#if defined(TELEMETRY_MAVLINK)
checkMAVLinkTelemetryState(); checkMAVLinkTelemetryState();
#endif
} }
void telemetryProcess(uint32_t currentTime, rxConfig_t *rxConfig, uint16_t deadband3d_throttle) void telemetryProcess(uint32_t currentTime, rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
@ -100,7 +107,10 @@ void telemetryProcess(uint32_t currentTime, rxConfig_t *rxConfig, uint16_t deadb
handleSmartPortTelemetry(); handleSmartPortTelemetry();
handleLtmTelemetry(); handleLtmTelemetry();
handleJetiExBusTelemetry(); handleJetiExBusTelemetry();
#if defined(TELEMETRY_MAVLINK)
handleMAVLinkTelemetry(); handleMAVLinkTelemetry();
#endif
} }
#endif #endif