1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-25 17:25:18 +03:00

Moved throttle percent calculation from MSP and OSD to Mixer

This commit is contained in:
Daniel Arruda Ribeiro 2021-01-15 18:12:45 -03:00
parent 2277239215
commit 101799952e
4 changed files with 11 additions and 14 deletions

View file

@ -830,16 +830,8 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU32(dst, getFlightTime()); // Flight time (seconds) sbufWriteU32(dst, getFlightTime()); // Flight time (seconds)
// Throttle // Throttle
int16_t thr = 0; sbufWriteU8(dst, throttlePercent); // Throttle Percent
const int minThrottle = getThrottleIdleValue(); sbufWriteU8(dst, navigationIsControllingThrottle() ? 1 : 0); // Auto Throttle Flag (0 or 1)
bool autoThrottle = navigationIsControllingThrottle();
if(autoThrottle)
thr = (constrain(rcCommand[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN);
else
thr = (constrain(rcCommand[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX ) - minThrottle) * 100 / (motorConfig()->maxthrottle - minThrottle);
sbufWriteU8(dst, thr); // Throttle Percent
sbufWriteU8(dst, autoThrottle ? 1 : 0); // Auto Throttle Flag (0 or 1)
break; break;

View file

@ -62,6 +62,7 @@ static float mixerScale = 1.0f;
static EXTENDED_FASTRAM motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS]; static EXTENDED_FASTRAM motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS];
static EXTENDED_FASTRAM uint8_t motorCount = 0; static EXTENDED_FASTRAM uint8_t motorCount = 0;
EXTENDED_FASTRAM int mixerThrottleCommand; EXTENDED_FASTRAM int mixerThrottleCommand;
EXTENDED_FASTRAM int throttlePercent;
static EXTENDED_FASTRAM int throttleIdleValue = 0; static EXTENDED_FASTRAM int throttleIdleValue = 0;
static EXTENDED_FASTRAM int motorValueWhenStopped = 0; static EXTENDED_FASTRAM int motorValueWhenStopped = 0;
static reversibleMotorsThrottleState_e reversibleMotorsThrottleState = MOTOR_DIRECTION_FORWARD; static reversibleMotorsThrottleState_e reversibleMotorsThrottleState = MOTOR_DIRECTION_FORWARD;
@ -529,6 +530,12 @@ void FAST_CODE mixTable(const float dT)
throttleRange = throttleMax - throttleMin; throttleRange = throttleMax - throttleMin;
// Throttle Percent used by OSD and MSP
if(navigationIsControllingThrottle())
throttlePercent = (constrain(mixerThrottleCommand, PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN);
else
throttlePercent = (constrain(mixerThrottleCommand, PWM_RANGE_MIN, PWM_RANGE_MAX) - throttleMin) * 100 / throttleRange;
#define THROTTLE_CLIPPING_FACTOR 0.33f #define THROTTLE_CLIPPING_FACTOR 0.33f
motorMixRange = (float)rpyMixRange / (float)throttleRange; motorMixRange = (float)rpyMixRange / (float)throttleRange;
if (motorMixRange > 1.0f) { if (motorMixRange > 1.0f) {

View file

@ -111,6 +111,7 @@ typedef enum {
extern int16_t motor[MAX_SUPPORTED_MOTORS]; extern int16_t motor[MAX_SUPPORTED_MOTORS];
extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS]; extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
extern int mixerThrottleCommand; extern int mixerThrottleCommand;
extern int throttlePercent;
int getThrottleIdleValue(void); int getThrottleIdleValue(void);
uint8_t getMotorCount(void); uint8_t getMotorCount(void);

View file

@ -869,18 +869,15 @@ void osdCrosshairPosition(uint8_t *x, uint8_t *y)
**/ **/
static void osdFormatThrottlePosition(char *buff, bool autoThr, textAttributes_t *elemAttr) static void osdFormatThrottlePosition(char *buff, bool autoThr, textAttributes_t *elemAttr)
{ {
const int minThrottle = getThrottleIdleValue();
buff[0] = SYM_BLANK; buff[0] = SYM_BLANK;
buff[1] = SYM_THR; buff[1] = SYM_THR;
int16_t thr = (constrain(rcCommand[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX ) - minThrottle) * 100 / (motorConfig()->maxthrottle - minThrottle);
if (autoThr && navigationIsControllingThrottle()) { if (autoThr && navigationIsControllingThrottle()) {
buff[0] = SYM_AUTO_THR0; buff[0] = SYM_AUTO_THR0;
buff[1] = SYM_AUTO_THR1; buff[1] = SYM_AUTO_THR1;
thr = (constrain(rcCommand[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN);
if (isFixedWingAutoThrottleManuallyIncreased()) if (isFixedWingAutoThrottleManuallyIncreased())
TEXT_ATTRIBUTES_ADD_BLINK(*elemAttr); TEXT_ATTRIBUTES_ADD_BLINK(*elemAttr);
} }
tfp_sprintf(buff + 2, "%3d", thr); tfp_sprintf(buff + 2, "%3d", throttlePercent);
} }
/** /**