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

Add OSD_THROTTLE_POS_AUTO_THR indicator

Displays stick THR position when the user controls THR directly,
actual applied THR when the navigation system controls THR.

Fixes #2031
This commit is contained in:
Alberto García Hierro 2017-09-17 22:33:03 +01:00
parent 2b79418712
commit 47fc453727
6 changed files with 44 additions and 3 deletions

View file

@ -208,6 +208,9 @@
#define SYM_THR 0x04
#define SYM_THR1 0x05
#define SYM_AUTO_THR0 202
#define SYM_AUTO_THR1 203
// RSSI
#define SYM_RSSI 0x01

View file

@ -1431,6 +1431,8 @@ groups:
max: OSD_POS_MAX_CLI
- name: osd_main_cell_voltage_pos
field: item_pos[OSD_MAIN_BATT_CELL_VOLTAGE]
- name: osd_throttle_auto_thr_pos
field: item_pos[OSD_THROTTLE_POS_AUTO_THR]
max: OSD_POS_MAX_CLI
- name: PG_SYSTEM_CONFIG

View file

@ -462,6 +462,25 @@ static void osdCrosshairsBounds(uint8_t *x, uint8_t *y, uint8_t *length)
}
}
/**
* Formats throttle position prefixed by its symbol. If autoThr
* is true and the navigation system is controlling THR, it
* uses the THR value applied by the system rather than the
* input value received by the sticks.
**/
static void osdFormatThrottlePosition(char *buff, bool autoThr)
{
buff[0] = SYM_THR;
buff[1] = SYM_THR1;
int16_t thr = rcData[THROTTLE];
if (autoThr && navigationIsControllingThrottle()) {
buff[0] = SYM_AUTO_THR0;
buff[1] = SYM_AUTO_THR1;
thr = rcCommand[THROTTLE];
}
tfp_sprintf(buff + 2, "%3d", (constrain(thr, PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN));
}
static bool osdDrawSingleElement(uint8_t item)
{
if (!VISIBLE(osdConfig()->item_pos[item])) {
@ -647,10 +666,10 @@ static bool osdDrawSingleElement(uint8_t item)
break;
case OSD_THROTTLE_POS:
buff[0] = SYM_THR;
buff[1] = SYM_THR1;
tfp_sprintf(buff + 2, "%3d", (constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN));
{
osdFormatThrottlePosition(buff, false);
break;
}
#ifdef VTX
case OSD_VTX_CHANNEL:
@ -926,6 +945,12 @@ static bool osdDrawSingleElement(uint8_t item)
break;
}
case OSD_THROTTLE_POS_AUTO_THR:
{
osdFormatThrottlePosition(buff, true);
break;
}
default:
return false;
}
@ -986,6 +1011,7 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig)
osdConfig->item_pos[OSD_GPS_SPEED] = OSD_POS(23, 1);
osdConfig->item_pos[OSD_THROTTLE_POS] = OSD_POS(1, 2) | VISIBLE_FLAG;
osdConfig->item_pos[OSD_THROTTLE_POS_AUTO_THR] = OSD_POS(6, 2);
osdConfig->item_pos[OSD_HEADING] = OSD_POS(12, 2);
osdConfig->item_pos[OSD_CURRENT_DRAW] = OSD_POS(1, 3) | VISIBLE_FLAG;
osdConfig->item_pos[OSD_MAH_DRAWN] = OSD_POS(1, 4) | VISIBLE_FLAG;

View file

@ -59,6 +59,7 @@ typedef enum {
OSD_MESSAGES,
OSD_GPS_HDOP,
OSD_MAIN_BATT_CELL_VOLTAGE,
OSD_THROTTLE_POS_AUTO_THR,
OSD_ITEM_COUNT // MUST BE LAST
} osd_items_e;

View file

@ -2693,6 +2693,11 @@ rthState_e getStateOfForcedRTH(void)
}
}
bool navigationIsControllingThrottle(void)
{
return posControl.navState != NAV_STATE_IDLE;
}
#else // NAV
#ifdef GPS

View file

@ -299,6 +299,9 @@ void activateForcedRTH(void);
void abortForcedRTH(void);
rthState_e getStateOfForcedRTH(void);
/* Getter functions which return data about the state of the navigation system */
bool navigationIsControllingThrottle(void);
/* Compatibility data */
extern navSystemStatus_t NAV_Status;
@ -320,5 +323,6 @@ extern int16_t navAccNEU[3];
#define navigationGetHeadingControlState() (0)
#define navigationRequiresThrottleTiltCompensation() (0)
#define getEstimatedActualVelocity(axis) (0)
#define navigationIsControllingThrottle() (0)
#endif