mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-26 17:55:30 +03:00
Improve code consistency by using function prefixes for telemetry
functions. PR's to make similar changes to other non-static functions are welcomed.
This commit is contained in:
parent
1673ad8b07
commit
e5a50654e3
9 changed files with 34 additions and 29 deletions
|
@ -662,7 +662,7 @@ void activateConfig(void)
|
||||||
useGyroConfig(&masterConfig.gyroConfig);
|
useGyroConfig(&masterConfig.gyroConfig);
|
||||||
|
|
||||||
#ifdef TELEMETRY
|
#ifdef TELEMETRY
|
||||||
useTelemetryConfig(&masterConfig.telemetryConfig);
|
telemetryUseConfig(&masterConfig.telemetryConfig);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
pidSetController(currentProfile->pidProfile.pidController);
|
pidSetController(currentProfile->pidProfile.pidController);
|
||||||
|
|
|
@ -299,7 +299,7 @@ void annexCode(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef TELEMETRY
|
#ifdef TELEMETRY
|
||||||
checkTelemetryState();
|
telemetryCheckState();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
handleSerial();
|
handleSerial();
|
||||||
|
@ -332,6 +332,14 @@ void mwDisarm(void)
|
||||||
|
|
||||||
#define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_MSP | FUNCTION_TELEMETRY_SMARTPORT)
|
#define TELEMETRY_FUNCTION_MASK (FUNCTION_TELEMETRY_FRSKY | FUNCTION_TELEMETRY_HOTT | FUNCTION_TELEMETRY_MSP | FUNCTION_TELEMETRY_SMARTPORT)
|
||||||
|
|
||||||
|
void releaseSharedTelemetryPorts(void) {
|
||||||
|
serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
|
||||||
|
while (sharedPort) {
|
||||||
|
mspReleasePortIfAllocated(sharedPort);
|
||||||
|
sharedPort = findNextSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void mwArm(void)
|
void mwArm(void)
|
||||||
{
|
{
|
||||||
if (ARMING_FLAG(OK_TO_ARM)) {
|
if (ARMING_FLAG(OK_TO_ARM)) {
|
||||||
|
@ -662,20 +670,17 @@ void processRx(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef TELEMETRY
|
#ifdef TELEMETRY
|
||||||
if (feature(FEATURE_TELEMETRY)) {
|
if (feature(FEATURE_TELEMETRY)) {
|
||||||
if ((!masterConfig.telemetryConfig.telemetry_switch && ARMING_FLAG(ARMED)) ||
|
if ((!masterConfig.telemetryConfig.telemetry_switch && ARMING_FLAG(ARMED)) ||
|
||||||
(masterConfig.telemetryConfig.telemetry_switch && IS_RC_MODE_ACTIVE(BOXTELEMETRY))) {
|
(masterConfig.telemetryConfig.telemetry_switch && IS_RC_MODE_ACTIVE(BOXTELEMETRY))) {
|
||||||
serialPort_t *sharedPort = findSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
|
|
||||||
while (sharedPort) {
|
releaseSharedTelemetryPorts();
|
||||||
mspReleasePortIfAllocated(sharedPort);
|
} else {
|
||||||
sharedPort = findNextSharedSerialPort(TELEMETRY_FUNCTION_MASK, FUNCTION_MSP);
|
|
||||||
}
|
|
||||||
} else {
|
|
||||||
// the telemetry state must be checked immediately so that shared serial ports are released.
|
// the telemetry state must be checked immediately so that shared serial ports are released.
|
||||||
checkTelemetryState();
|
telemetryCheckState();
|
||||||
mspAllocateSerialPorts(&masterConfig.serialConfig);
|
mspAllocateSerialPorts(&masterConfig.serialConfig);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
}
|
}
|
||||||
|
@ -814,7 +819,7 @@ void loop(void)
|
||||||
|
|
||||||
#ifdef TELEMETRY
|
#ifdef TELEMETRY
|
||||||
if (!cliMode && feature(FEATURE_TELEMETRY)) {
|
if (!cliMode && feature(FEATURE_TELEMETRY)) {
|
||||||
handleTelemetry(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle);
|
telemetryProcess(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -472,7 +472,7 @@ bool hasEnoughTimeLapsedSinceLastTelemetryTransmission(uint32_t currentMillis)
|
||||||
|
|
||||||
void checkFrSkyTelemetryState(void)
|
void checkFrSkyTelemetryState(void)
|
||||||
{
|
{
|
||||||
bool newTelemetryEnabledValue = determineNewTelemetryEnabledState(frskyPortSharing);
|
bool newTelemetryEnabledValue = telemetryDetermineEnabledState(frskyPortSharing);
|
||||||
|
|
||||||
if (newTelemetryEnabledValue == frskyTelemetryEnabled) {
|
if (newTelemetryEnabledValue == frskyTelemetryEnabled) {
|
||||||
return;
|
return;
|
||||||
|
|
|
@ -462,7 +462,7 @@ static inline bool shouldCheckForHoTTRequest()
|
||||||
|
|
||||||
void checkHoTTTelemetryState(void)
|
void checkHoTTTelemetryState(void)
|
||||||
{
|
{
|
||||||
bool newTelemetryEnabledValue = determineNewTelemetryEnabledState(hottPortSharing);
|
bool newTelemetryEnabledValue = telemetryDetermineEnabledState(hottPortSharing);
|
||||||
|
|
||||||
if (newTelemetryEnabledValue == hottTelemetryEnabled) {
|
if (newTelemetryEnabledValue == hottTelemetryEnabled) {
|
||||||
return;
|
return;
|
||||||
|
|
|
@ -57,7 +57,7 @@ void initMSPTelemetry(telemetryConfig_t *initialTelemetryConfig)
|
||||||
|
|
||||||
void checkMSPTelemetryState(void)
|
void checkMSPTelemetryState(void)
|
||||||
{
|
{
|
||||||
bool newTelemetryEnabledValue = determineNewTelemetryEnabledState(mspPortSharing);
|
bool newTelemetryEnabledValue = telemetryDetermineEnabledState(mspPortSharing);
|
||||||
|
|
||||||
if (newTelemetryEnabledValue == mspTelemetryEnabled) {
|
if (newTelemetryEnabledValue == mspTelemetryEnabled) {
|
||||||
return;
|
return;
|
||||||
|
|
|
@ -261,7 +261,7 @@ bool isSmartPortTimedOut(void)
|
||||||
|
|
||||||
void checkSmartPortTelemetryState(void)
|
void checkSmartPortTelemetryState(void)
|
||||||
{
|
{
|
||||||
bool newTelemetryEnabledValue = determineNewTelemetryEnabledState(smartPortPortSharing);
|
bool newTelemetryEnabledValue = telemetryDetermineEnabledState(smartPortPortSharing);
|
||||||
|
|
||||||
if (newTelemetryEnabledValue == smartPortTelemetryEnabled) {
|
if (newTelemetryEnabledValue == smartPortTelemetryEnabled) {
|
||||||
return;
|
return;
|
||||||
|
|
|
@ -43,7 +43,7 @@
|
||||||
|
|
||||||
static telemetryConfig_t *telemetryConfig;
|
static telemetryConfig_t *telemetryConfig;
|
||||||
|
|
||||||
void useTelemetryConfig(telemetryConfig_t *telemetryConfigToUse)
|
void telemetryUseConfig(telemetryConfig_t *telemetryConfigToUse)
|
||||||
{
|
{
|
||||||
telemetryConfig = telemetryConfigToUse;
|
telemetryConfig = telemetryConfigToUse;
|
||||||
}
|
}
|
||||||
|
@ -55,10 +55,10 @@ void telemetryInit(void)
|
||||||
initMSPTelemetry(telemetryConfig);
|
initMSPTelemetry(telemetryConfig);
|
||||||
initSmartPortTelemetry(telemetryConfig);
|
initSmartPortTelemetry(telemetryConfig);
|
||||||
|
|
||||||
checkTelemetryState();
|
telemetryCheckState();
|
||||||
}
|
}
|
||||||
|
|
||||||
bool determineNewTelemetryEnabledState(portSharing_e portSharing)
|
bool telemetryDetermineEnabledState(portSharing_e portSharing)
|
||||||
{
|
{
|
||||||
bool enabled = portSharing == PORTSHARING_NOT_SHARED;
|
bool enabled = portSharing == PORTSHARING_NOT_SHARED;
|
||||||
|
|
||||||
|
@ -72,7 +72,7 @@ bool determineNewTelemetryEnabledState(portSharing_e portSharing)
|
||||||
return enabled;
|
return enabled;
|
||||||
}
|
}
|
||||||
|
|
||||||
void checkTelemetryState(void)
|
void telemetryCheckState(void)
|
||||||
{
|
{
|
||||||
checkFrSkyTelemetryState();
|
checkFrSkyTelemetryState();
|
||||||
checkHoTTTelemetryState();
|
checkHoTTTelemetryState();
|
||||||
|
@ -80,7 +80,7 @@ void checkTelemetryState(void)
|
||||||
checkSmartPortTelemetryState();
|
checkSmartPortTelemetryState();
|
||||||
}
|
}
|
||||||
|
|
||||||
void handleTelemetry(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
void telemetryProcess(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
||||||
{
|
{
|
||||||
handleFrSkyTelemetry(rxConfig, deadband3d_throttle);
|
handleFrSkyTelemetry(rxConfig, deadband3d_throttle);
|
||||||
handleHoTTTelemetry();
|
handleHoTTTelemetry();
|
||||||
|
|
|
@ -47,11 +47,11 @@ typedef struct telemetryConfig_s {
|
||||||
uint8_t hottAlarmSoundInterval;
|
uint8_t hottAlarmSoundInterval;
|
||||||
} telemetryConfig_t;
|
} telemetryConfig_t;
|
||||||
|
|
||||||
void checkTelemetryState(void);
|
void telemetryCheckState(void);
|
||||||
void handleTelemetry(rxConfig_t *rxConfig, uint16_t deadband3d_throttle);
|
void telemetryProcess(rxConfig_t *rxConfig, uint16_t deadband3d_throttle);
|
||||||
|
|
||||||
bool determineNewTelemetryEnabledState(portSharing_e portSharing);
|
bool telemetryDetermineEnabledState(portSharing_e portSharing);
|
||||||
|
|
||||||
void useTelemetryConfig(telemetryConfig_t *telemetryConfig);
|
void telemetryUseConfig(telemetryConfig_t *telemetryConfig);
|
||||||
|
|
||||||
#endif /* TELEMETRY_COMMON_H_ */
|
#endif /* TELEMETRY_COMMON_H_ */
|
||||||
|
|
|
@ -224,7 +224,7 @@ bool sensors(uint32_t mask) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool determineNewTelemetryEnabledState(portSharing_e) {
|
bool telemetryDetermineEnabledState(portSharing_e) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue