mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-24 16:55:29 +03:00
Merge pull request #8806 from iNavFlight/MrD_OSD-Throttle-Options
Update OSD throttle options
This commit is contained in:
commit
2d7a057d03
10 changed files with 51 additions and 20 deletions
|
@ -190,8 +190,8 @@ static const OSD_Entry menuOsdElemsEntries[] =
|
|||
OSD_ELEMENT_ENTRY("TIME (HOUR)", OSD_RTC_TIME),
|
||||
OSD_ELEMENT_ENTRY("FLY MODE", OSD_FLYMODE),
|
||||
OSD_ELEMENT_ENTRY("NAME", OSD_CRAFT_NAME),
|
||||
OSD_ELEMENT_ENTRY("THR. (MANU)", OSD_THROTTLE_POS),
|
||||
OSD_ELEMENT_ENTRY("THR. (MANU/AUTO)", OSD_THROTTLE_POS_AUTO_THR),
|
||||
OSD_ELEMENT_ENTRY("THR. ", OSD_THROTTLE_POS),
|
||||
OSD_ELEMENT_ENTRY("THR. (SCALED)", OSD_SCALED_THROTTLE_POS),
|
||||
OSD_ELEMENT_ENTRY("SYS MESSAGES", OSD_MESSAGES),
|
||||
OSD_ELEMENT_ENTRY("VTX CHAN", OSD_VTX_CHANNEL),
|
||||
OSD_ELEMENT_ENTRY("CURRENT (A)", OSD_CURRENT_DRAW),
|
||||
|
|
|
@ -834,7 +834,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU32(dst, getFlightTime()); // Flight time (seconds)
|
||||
|
||||
// Throttle
|
||||
sbufWriteU8(dst, getThrottlePercent()); // Throttle Percent
|
||||
sbufWriteU8(dst, getThrottlePercent(true)); // Throttle Percent
|
||||
sbufWriteU8(dst, navigationIsControllingThrottle() ? 1 : 0); // Auto Throttle Flag (0 or 1)
|
||||
|
||||
break;
|
||||
|
|
|
@ -612,9 +612,16 @@ void FAST_CODE mixTable()
|
|||
}
|
||||
}
|
||||
|
||||
int16_t getThrottlePercent(void)
|
||||
int16_t getThrottlePercent(bool useScaled)
|
||||
{
|
||||
int16_t thr = (constrain(rcCommand[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX ) - getThrottleIdleValue()) * 100 / (motorConfig()->maxthrottle - getThrottleIdleValue());
|
||||
int16_t thr = constrain(rcCommand[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX);
|
||||
const int idleThrottle = getThrottleIdleValue();
|
||||
|
||||
if (useScaled) {
|
||||
thr = (thr - idleThrottle) * 100 / (motorConfig()->maxthrottle - idleThrottle);
|
||||
} else {
|
||||
thr = (rxGetChannelValue(THROTTLE) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN);
|
||||
}
|
||||
return thr;
|
||||
}
|
||||
|
||||
|
|
|
@ -111,7 +111,7 @@ extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
|
|||
extern int mixerThrottleCommand;
|
||||
|
||||
int getThrottleIdleValue(void);
|
||||
int16_t getThrottlePercent(void);
|
||||
int16_t getThrottlePercent(bool);
|
||||
uint8_t getMotorCount(void);
|
||||
float getMotorMixRange(void);
|
||||
bool mixerIsOutputSaturated(void);
|
||||
|
|
|
@ -1079,26 +1079,46 @@ void osdCrosshairPosition(uint8_t *x, uint8_t *y)
|
|||
}
|
||||
|
||||
/**
|
||||
* Formats throttle position prefixed by its symbol.
|
||||
* Shows output to motor, not stick position
|
||||
**/
|
||||
static void osdFormatThrottlePosition(char *buff, bool autoThr, textAttributes_t *elemAttr)
|
||||
* Check if this OSD layout is using scaled or unscaled throttle.
|
||||
* If both are used, it will default to scaled.
|
||||
*/
|
||||
bool osdUsingScaledThrottle()
|
||||
{
|
||||
buff[0] = SYM_BLANK;
|
||||
bool usingScaledThrottle = OSD_VISIBLE(osdLayoutsConfig()->item_pos[currentLayout][OSD_SCALED_THROTTLE_POS]);
|
||||
bool usingRCThrottle = OSD_VISIBLE(osdLayoutsConfig()->item_pos[currentLayout][OSD_THROTTLE_POS]);
|
||||
|
||||
if (!usingScaledThrottle && !usingRCThrottle)
|
||||
usingScaledThrottle = true;
|
||||
|
||||
return usingScaledThrottle;
|
||||
}
|
||||
|
||||
/**
|
||||
* Formats throttle position prefixed by its symbol.
|
||||
* Shows unscaled or scaled (output to motor) throttle percentage
|
||||
**/
|
||||
static void osdFormatThrottlePosition(char *buff, bool useScaled, textAttributes_t *elemAttr)
|
||||
{
|
||||
if (useScaled) {
|
||||
buff[0] = SYM_SCALE;
|
||||
} else {
|
||||
buff[0] = SYM_BLANK;
|
||||
}
|
||||
buff[1] = SYM_THR;
|
||||
if (autoThr && navigationIsControllingThrottle()) {
|
||||
if (navigationIsControllingThrottle()) {
|
||||
buff[0] = SYM_AUTO_THR0;
|
||||
buff[1] = SYM_AUTO_THR1;
|
||||
if (isFixedWingAutoThrottleManuallyIncreased()) {
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(*elemAttr);
|
||||
}
|
||||
useScaled = true;
|
||||
}
|
||||
#ifdef USE_POWER_LIMITS
|
||||
if (powerLimiterIsLimiting()) {
|
||||
TEXT_ATTRIBUTES_ADD_BLINK(*elemAttr);
|
||||
}
|
||||
#endif
|
||||
tfp_sprintf(buff + 2, "%3d", getThrottlePercent());
|
||||
tfp_sprintf(buff + 2, "%3d", getThrottlePercent(useScaled));
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -2893,7 +2913,7 @@ static bool osdDrawSingleElement(uint8_t item)
|
|||
return true;
|
||||
}
|
||||
|
||||
case OSD_THROTTLE_POS_AUTO_THR:
|
||||
case OSD_SCALED_THROTTLE_POS:
|
||||
{
|
||||
osdFormatThrottlePosition(buff, true, &elemAttr);
|
||||
break;
|
||||
|
@ -3704,7 +3724,7 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig)
|
|||
osdLayoutsConfig->item_pos[0][OSD_GLIDESLOPE] = OSD_POS(23, 2);
|
||||
|
||||
osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS] = OSD_POS(1, 2) | OSD_VISIBLE_FLAG;
|
||||
osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS_AUTO_THR] = OSD_POS(6, 2);
|
||||
osdLayoutsConfig->item_pos[0][OSD_SCALED_THROTTLE_POS] = OSD_POS(6, 2);
|
||||
osdLayoutsConfig->item_pos[0][OSD_HEADING] = OSD_POS(12, 2);
|
||||
osdLayoutsConfig->item_pos[0][OSD_GROUND_COURSE] = OSD_POS(12, 3);
|
||||
osdLayoutsConfig->item_pos[0][OSD_COURSE_HOLD_ERROR] = OSD_POS(12, 2);
|
||||
|
|
|
@ -162,7 +162,7 @@ typedef enum {
|
|||
OSD_MESSAGES,
|
||||
OSD_GPS_HDOP,
|
||||
OSD_MAIN_BATT_CELL_VOLTAGE,
|
||||
OSD_THROTTLE_POS_AUTO_THR,
|
||||
OSD_SCALED_THROTTLE_POS,
|
||||
OSD_HEADING_GRAPH,
|
||||
OSD_EFFICIENCY_MAH_PER_KM,
|
||||
OSD_WH_DRAWN,
|
||||
|
@ -476,6 +476,8 @@ displayCanvas_t *osdGetDisplayPortCanvas(void);
|
|||
int16_t osdGetHeading(void);
|
||||
int32_t osdGetAltitude(void);
|
||||
|
||||
bool osdUsingScaledThrottle(void);
|
||||
|
||||
void osdStartedSaveProcess(void);
|
||||
void osdShowEEPROMSavedNotification(void);
|
||||
|
||||
|
|
|
@ -1110,7 +1110,7 @@ static void djiSerializeCraftNameOverride(sbuf_t *dst)
|
|||
activeElements[activeElementsCount++] = DJI_OSD_CN_THROTTLE;
|
||||
}
|
||||
|
||||
if (OSD_VISIBLE(osdLayoutConfig[OSD_THROTTLE_POS_AUTO_THR])) {
|
||||
if (OSD_VISIBLE(osdLayoutConfig[OSD_SCALED_THROTTLE_POS])) {
|
||||
activeElements[activeElementsCount++] = DJI_OSD_CN_THROTTLE_AUTO_THR;
|
||||
}
|
||||
|
||||
|
|
|
@ -47,6 +47,7 @@
|
|||
#include "flight/imu.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
#include "io/osd.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
@ -195,7 +196,7 @@ static void sendThrottleOrBatterySizeAsRpm(void)
|
|||
{
|
||||
sendDataHead(ID_RPM);
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
uint16_t throttleForRPM = getThrottlePercent() / BLADE_NUMBER_DIVIDER;
|
||||
uint16_t throttleForRPM = getThrottlePercent(osdUsingScaledThrottle()) / BLADE_NUMBER_DIVIDER;
|
||||
serialize16(throttleForRPM);
|
||||
} else {
|
||||
serialize16((currentBatteryProfile->capacity.value / BLADE_NUMBER_DIVIDER));
|
||||
|
|
|
@ -33,6 +33,7 @@
|
|||
#include "fc/runtime_config.h"
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
#include "io/osd.h"
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "sensors/barometer.h"
|
||||
|
@ -147,7 +148,7 @@ static uint8_t dispatchMeasurementRequest(ibusAddress_t address) {
|
|||
if (!temp_valid || (temperature < -400)) temperature = -400; // Minimum reported temperature is -40°C
|
||||
return sendIbusMeasurement2(address, (uint16_t)(temperature + IBUS_TEMPERATURE_OFFSET));
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_RPM) {
|
||||
return sendIbusMeasurement2(address, (uint16_t)getThrottlePercent() );
|
||||
return sendIbusMeasurement2(address, (uint16_t)getThrottlePercent(osdUsingScaledThrottle()) );
|
||||
} else if (SENSOR_ADDRESS_TYPE_LOOKUP[address].value == IBUS_MEAS_VALUE_EXTERNAL_VOLTAGE) { //VBAT
|
||||
if (telemetryConfig()->report_cell_voltage) {
|
||||
return sendIbusMeasurement2(address, getBatteryAverageCellVoltage());
|
||||
|
|
|
@ -653,7 +653,7 @@ void mavlinkSendHUDAndHeartbeat(void)
|
|||
mavAltitude = getEstimatedActualPosition(Z) / 100.0f;
|
||||
mavClimbRate = getEstimatedActualVelocity(Z) / 100.0f;
|
||||
|
||||
int16_t thr = getThrottlePercent();
|
||||
int16_t thr = getThrottlePercent(osdUsingScaledThrottle());
|
||||
mavlink_msg_vfr_hud_pack(mavSystemId, mavComponentId, &mavSendMsg,
|
||||
// airspeed Current airspeed in m/s
|
||||
mavAirSpeed,
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue