1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-20 06:45:16 +03:00

Merge pull request #6233 from leocb/add-gforce-osd

Added G-Force to the OSD
This commit is contained in:
Michael Keller 2018-07-17 18:28:58 +12:00 committed by GitHub
commit e2cf7fc238
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
8 changed files with 25 additions and 1 deletions

View file

@ -102,6 +102,7 @@ OSD_Entry menuOsdActiveElemsEntries[] =
{"ROL ANG", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_ROLL_ANGLE], 0},
{"HEADING", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_NUMERICAL_HEADING], 0},
{"VARIO", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_NUMERICAL_VARIO], 0},
{"G-FORCE", OME_VISIBLE, NULL, &osdConfig_item_pos[OSD_G_FORCE], 0},
{"BACK", OME_Back, NULL, NULL, 0},
{NULL, OME_END, NULL, NULL, 0}
};

View file

@ -85,6 +85,7 @@ static bool imuUpdated = false;
#define GPS_COG_MIN_GROUNDSPEED 500 // 500cm/s minimum groundspeed for a gps heading to be considered valid
int32_t accSum[XYZ_AXIS_COUNT];
float accAverage[XYZ_AXIS_COUNT];
uint32_t accTimeSum = 0; // keep track for integration of acc
int accSumCount = 0;
@ -491,7 +492,6 @@ static void imuCalculateEstimatedAttitude(timeUs_t currentTimeUs)
#endif
float gyroAverage[XYZ_AXIS_COUNT];
gyroGetAccumulationAverage(gyroAverage);
float accAverage[XYZ_AXIS_COUNT];
if (accGetAccumulationAverage(accAverage)) {
useAcc = imuIsAccelerometerHealthy(accAverage);
}

View file

@ -31,6 +31,7 @@ extern int accSumCount;
extern float accVelScale;
extern int32_t accSum[XYZ_AXIS_COUNT];
extern bool canUseGPSHeading;
extern float accAverage[XYZ_AXIS_COUNT];
typedef struct {
float w,x,y,z;

View file

@ -927,6 +927,7 @@ const clivalue_t valueTable[] = {
{ "osd_remaining_time_estimate_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_REMAINING_TIME_ESTIMATE]) },
{ "osd_flymode_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_FLYMODE]) },
{ "osd_anti_gravity_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ANTI_GRAVITY]) },
{ "osd_g_force_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_G_FORCE]) },
{ "osd_throttle_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_THROTTLE_POS]) },
{ "osd_vtx_channel_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_VTX_CHANNEL]) },
{ "osd_crosshairs_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_CROSSHAIRS]) },

View file

@ -46,6 +46,7 @@
#include "cms/cms.h"
#include "cms/cms_types.h"
#include "common/axis.h"
#include "common/maths.h"
#include "common/printf.h"
#include "common/typeconversion.h"
@ -87,6 +88,7 @@
#include "rx/rx.h"
#include "sensors/acceleration.h"
#include "sensors/adcinternal.h"
#include "sensors/barometer.h"
#include "sensors/battery.h"
@ -690,6 +692,18 @@ static bool osdDrawSingleElement(uint8_t item)
return true;
}
case OSD_G_FORCE:
{
float osdGForce = 0;
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
const float a = accAverage[axis];
osdGForce += a * a;
}
osdGForce = sqrtf(osdGForce) / acc.dev.acc_1G;
tfp_sprintf(buff, "%01d.%01dG", (int)osdGForce, (int)(osdGForce * 10) % 10);
break;
}
case OSD_ROLL_PIDS:
osdFormatPID(buff, "ROL", &currentPidProfile->pid[PID_ROLL]);
break;
@ -976,6 +990,7 @@ static void osdDrawElements(void)
if (sensors(SENSOR_ACC)) {
osdDrawSingleElement(OSD_ARTIFICIAL_HORIZON);
osdDrawSingleElement(OSD_G_FORCE);
}

View file

@ -95,6 +95,7 @@ typedef enum {
OSD_ADJUSTMENT_RANGE,
OSD_CORE_TEMPERATURE,
OSD_ANTI_GRAVITY,
OSD_G_FORCE,
OSD_ITEM_COUNT // MUST BE LAST
} osd_items_e;

View file

@ -150,6 +150,7 @@ void targetConfiguration(void)
osdConfigMutable()->item_pos[OSD_NUMERICAL_VARIO] &= ~VISIBLE_FLAG;
osdConfigMutable()->item_pos[OSD_ESC_TMP] &= ~VISIBLE_FLAG;
osdConfigMutable()->item_pos[OSD_ESC_RPM] &= ~VISIBLE_FLAG;
osdConfigMutable()->item_pos[OSD_G_FORCE] &= ~VISIBLE_FLAG;
modeActivationConditionsMutable(0)->modeId = BOXANGLE;
modeActivationConditionsMutable(0)->auxChannelIndex = AUX2 - NON_AUX_CHANNEL_COUNT;

View file

@ -49,6 +49,7 @@ extern "C" {
#include "io/gps.h"
#include "io/osd.h"
#include "sensors/acceleration.h"
#include "sensors/battery.h"
#include "rx/rx.h"
@ -69,6 +70,9 @@ extern "C" {
int32_t GPS_coord[2];
gpsSolutionData_t gpsSol;
acc_t acc;
float accAverage[XYZ_AXIS_COUNT];
PG_REGISTER(batteryConfig_t, batteryConfig, PG_BATTERY_CONFIG, 0);
PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
PG_REGISTER(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);