Merge pull request #699 from pinkywafer/frsky_RPM_telemetry_fix
FrSky RPM Telemetry Motor_Stop Bugfix
This commit is contained in:
commit
7efdcf13e3
|
@ -747,7 +747,7 @@ void loop(void)
|
|||
|
||||
#ifdef TELEMETRY
|
||||
if (!cliMode && feature(FEATURE_TELEMETRY)) {
|
||||
handleTelemetry();
|
||||
handleTelemetry(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -193,11 +193,15 @@ static void sendGpsAltitude(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
static void sendThrottleOrBatterySizeAsRpm(void)
|
||||
static void sendThrottleOrBatterySizeAsRpm(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
||||
{
|
||||
uint16_t throttleForRPM = rcCommand[THROTTLE] / BLADE_NUMBER_DIVIDER;
|
||||
sendDataHead(ID_RPM);
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
serialize16(rcCommand[THROTTLE] / BLADE_NUMBER_DIVIDER);
|
||||
throttleStatus_e throttleStatus = calculateThrottleStatus(rxConfig, deadband3d_throttle);
|
||||
if (throttleStatus == THROTTLE_LOW && feature(FEATURE_MOTOR_STOP))
|
||||
throttleForRPM = 0;
|
||||
serialize16(throttleForRPM);
|
||||
} else {
|
||||
serialize16((batteryConfig->batteryCapacity / BLADE_NUMBER_DIVIDER));
|
||||
}
|
||||
|
@ -460,7 +464,7 @@ void checkFrSkyTelemetryState(void)
|
|||
freeFrSkyTelemetryPort();
|
||||
}
|
||||
|
||||
void handleFrSkyTelemetry(void)
|
||||
void handleFrSkyTelemetry(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
||||
{
|
||||
if (!frskyTelemetryEnabled) {
|
||||
return;
|
||||
|
@ -491,7 +495,7 @@ void handleFrSkyTelemetry(void)
|
|||
|
||||
if ((cycleNum % 8) == 0) { // Sent every 1s
|
||||
sendTemperature1();
|
||||
sendThrottleOrBatterySizeAsRpm();
|
||||
sendThrottleOrBatterySizeAsRpm(rxConfig, deadband3d_throttle);
|
||||
|
||||
if (feature(FEATURE_VBAT)) {
|
||||
sendVoltage();
|
||||
|
|
|
@ -15,6 +15,8 @@
|
|||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#ifndef TELEMETRY_FRSKY_H_
|
||||
#define TELEMETRY_FRSKY_H_
|
||||
|
||||
|
@ -23,7 +25,7 @@ typedef enum {
|
|||
FRSKY_VFAS_PRECISION_HIGH
|
||||
} frskyVFasPrecision_e;
|
||||
|
||||
void handleFrSkyTelemetry(void);
|
||||
void handleFrSkyTelemetry(rxConfig_t *rxConfig, uint16_t deadband3d_throttle);
|
||||
void checkFrSkyTelemetryState(void);
|
||||
|
||||
void initFrSkyTelemetry(telemetryConfig_t *telemetryConfig);
|
||||
|
|
|
@ -80,9 +80,9 @@ void checkTelemetryState(void)
|
|||
checkSmartPortTelemetryState();
|
||||
}
|
||||
|
||||
void handleTelemetry(void)
|
||||
void handleTelemetry(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
|
||||
{
|
||||
handleFrSkyTelemetry();
|
||||
handleFrSkyTelemetry(rxConfig, deadband3d_throttle);
|
||||
handleHoTTTelemetry();
|
||||
handleMSPTelemetry();
|
||||
handleSmartPortTelemetry();
|
||||
|
|
|
@ -21,6 +21,7 @@
|
|||
* Created on: 6 Apr 2014
|
||||
* Author: Hydra
|
||||
*/
|
||||
#include "rx/rx.h"
|
||||
|
||||
#ifndef TELEMETRY_COMMON_H_
|
||||
#define TELEMETRY_COMMON_H_
|
||||
|
@ -46,7 +47,7 @@ typedef struct telemetryConfig_s {
|
|||
} telemetryConfig_t;
|
||||
|
||||
void checkTelemetryState(void);
|
||||
void handleTelemetry(void);
|
||||
void handleTelemetry(rxConfig_t *rxConfig, uint16_t deadband3d_throttle);
|
||||
|
||||
bool determineNewTelemetryEnabledState(portSharing_e portSharing);
|
||||
|
||||
|
|
Loading…
Reference in New Issue