Merge pull request #2436 from martinbudden/bf_pg_preparation13
Preparation for conversion to parameter groups 13
This commit is contained in:
commit
743b3e37e3
|
@ -31,7 +31,8 @@
|
|||
|
||||
#include "build/version.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
#include "blackbox/blackbox.h"
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
#include "cms/cms.h"
|
||||
#include "cms/cms_types.h"
|
||||
|
@ -44,11 +45,12 @@
|
|||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
#include "io/flashfs.h"
|
||||
#include "io/beeper.h"
|
||||
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
#ifdef USE_FLASHFS
|
||||
static long cmsx_EraseFlash(displayPort_t *pDisplay, const void *ptr)
|
||||
|
@ -178,7 +180,7 @@ static long cmsx_Blackbox_onExit(const OSD_Entry *self)
|
|||
UNUSED(self);
|
||||
|
||||
if (blackboxMayEditConfig()) {
|
||||
blackboxConfig()->device = cmsx_BlackboxDevice;
|
||||
blackboxConfigMutable()->device = cmsx_BlackboxDevice;
|
||||
validateBlackboxConfig();
|
||||
}
|
||||
|
||||
|
|
|
@ -43,6 +43,7 @@
|
|||
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "config/config_master.h"
|
||||
#include "config/config_profile.h"
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
|
|
|
@ -37,6 +37,13 @@
|
|||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
|
||||
|
||||
//
|
||||
// Misc
|
||||
//
|
||||
|
|
|
@ -34,10 +34,12 @@
|
|||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
OSD_UINT8_t entryAlarmRssi = {&osdProfile()->rssi_alarm, 5, 90, 5};
|
||||
OSD_UINT16_t entryAlarmCapacity = {&osdProfile()->cap_alarm, 50, 30000, 50};
|
||||
OSD_UINT16_t enryAlarmFlyTime = {&osdProfile()->time_alarm, 1, 200, 1};
|
||||
OSD_UINT16_t entryAlarmAltitude = {&osdProfile()->alt_alarm, 1, 200, 1};
|
||||
#include "io/osd.h"
|
||||
|
||||
OSD_UINT8_t entryAlarmRssi = {&osdConfig()->rssi_alarm, 5, 90, 5};
|
||||
OSD_UINT16_t entryAlarmCapacity = {&osdConfig()->cap_alarm, 50, 30000, 50};
|
||||
OSD_UINT16_t enryAlarmFlyTime = {&osdConfig()->time_alarm, 1, 200, 1};
|
||||
OSD_UINT16_t entryAlarmAltitude = {&osdConfig()->alt_alarm, 1, 200, 1};
|
||||
|
||||
OSD_Entry cmsx_menuAlarmsEntries[] =
|
||||
{
|
||||
|
@ -62,29 +64,29 @@ CMS_Menu cmsx_menuAlarms = {
|
|||
OSD_Entry menuOsdActiveElemsEntries[] =
|
||||
{
|
||||
{"--- ACTIV ELEM ---", OME_Label, NULL, NULL, 0},
|
||||
{"RSSI", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_RSSI_VALUE], 0},
|
||||
{"MAIN BATTERY", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_MAIN_BATT_VOLTAGE], 0},
|
||||
{"HORIZON", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_ARTIFICIAL_HORIZON], 0},
|
||||
{"HORIZON SIDEBARS", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_HORIZON_SIDEBARS], 0},
|
||||
{"UPTIME", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_ONTIME], 0},
|
||||
{"FLY TIME", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_FLYTIME], 0},
|
||||
{"FLY MODE", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_FLYMODE], 0},
|
||||
{"NAME", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_CRAFT_NAME], 0},
|
||||
{"THROTTLE", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_THROTTLE_POS], 0},
|
||||
{"RSSI", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_RSSI_VALUE], 0},
|
||||
{"MAIN BATTERY", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_MAIN_BATT_VOLTAGE], 0},
|
||||
{"HORIZON", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_ARTIFICIAL_HORIZON], 0},
|
||||
{"HORIZON SIDEBARS", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_HORIZON_SIDEBARS], 0},
|
||||
{"UPTIME", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_ONTIME], 0},
|
||||
{"FLY TIME", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_FLYTIME], 0},
|
||||
{"FLY MODE", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_FLYMODE], 0},
|
||||
{"NAME", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_CRAFT_NAME], 0},
|
||||
{"THROTTLE", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_THROTTLE_POS], 0},
|
||||
#ifdef VTX
|
||||
{"VTX CHAN", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_VTX_CHANNEL], 0},
|
||||
{"VTX CHAN", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_VTX_CHANNEL], 0},
|
||||
#endif // VTX
|
||||
{"CURRENT (A)", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_CURRENT_DRAW], 0},
|
||||
{"USED MAH", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_MAH_DRAWN], 0},
|
||||
{"CURRENT (A)", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_CURRENT_DRAW], 0},
|
||||
{"USED MAH", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_MAH_DRAWN], 0},
|
||||
#ifdef GPS
|
||||
{"GPS SPEED", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_GPS_SPEED], 0},
|
||||
{"GPS SATS.", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_GPS_SATS], 0},
|
||||
{"GPS SPEED", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_GPS_SPEED], 0},
|
||||
{"GPS SATS.", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_GPS_SATS], 0},
|
||||
#endif // GPS
|
||||
{"ALTITUDE", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_ALTITUDE], 0},
|
||||
{"POWER", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_POWER], 0},
|
||||
{"ROLL PID", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_ROLL_PIDS], 0},
|
||||
{"PITCH PID", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_PITCH_PIDS], 0},
|
||||
{"YAW PID", OME_VISIBLE, NULL, &osdProfile()->item_pos[OSD_YAW_PIDS], 0},
|
||||
{"ALTITUDE", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_ALTITUDE], 0},
|
||||
{"POWER", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_POWER], 0},
|
||||
{"ROLL PID", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_ROLL_PIDS], 0},
|
||||
{"PITCH PID", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_PITCH_PIDS], 0},
|
||||
{"YAW PID", OME_VISIBLE, NULL, &osdConfig()->item_pos[OSD_YAW_PIDS], 0},
|
||||
{"BACK", OME_Back, NULL, NULL, 0},
|
||||
{NULL, OME_END, NULL, NULL, 0}
|
||||
};
|
||||
|
|
|
@ -103,7 +103,7 @@
|
|||
#define sonarConfig(x) (&masterConfig.sonarConfig)
|
||||
#define ledStripConfig(x) (&masterConfig.ledStripConfig)
|
||||
#define statusLedConfig(x) (&masterConfig.statusLedConfig)
|
||||
#define osdProfile(x) (&masterConfig.osdProfile)
|
||||
#define osdConfig(x) (&masterConfig.osdProfile)
|
||||
#define vcdProfile(x) (&masterConfig.vcdProfile)
|
||||
#define sdcardConfig(x) (&masterConfig.sdcardConfig)
|
||||
#define blackboxConfig(x) (&masterConfig.blackboxConfig)
|
||||
|
@ -173,8 +173,8 @@
|
|||
#define osdConfig(x) (&masterConfig.osdProfile)
|
||||
#define modeActivationConditions(x) (&masterConfig.modeActivationProfile.modeActivationConditions[x])
|
||||
|
||||
#define servoParamsMutable(x) (&servoProfile()->servoConf[i])
|
||||
#define adjustmentRangesMutable(x) (&masterConfig.adjustmentProfile.adjustmentRanges[i])
|
||||
#define servoParamsMutable(x) (&servoProfile()->servoConf[x])
|
||||
#define adjustmentRangesMutable(x) (&masterConfig.adjustmentProfile.adjustmentRanges[x])
|
||||
#define rxFailsafeChannelConfigsMutable(x) (&masterConfig.rxConfig.>failsafe_channel_configurations[x])
|
||||
#define osdConfigMutable(x) (&masterConfig.osdProfile)
|
||||
#define modeActivationConditionsMutable(x) (&masterConfig.modeActivationProfile.modeActivationConditions[x])
|
||||
|
|
|
@ -59,7 +59,7 @@
|
|||
#define PG_ADJUSTMENT_RANGE_CONFIG 37
|
||||
#define PG_BAROMETER_CONFIG 38 // structs OK
|
||||
#define PG_THROTTLE_CORRECTION_CONFIG 39
|
||||
#define PG_COMPASS_CONFIGURATION 40 // structs OK
|
||||
#define PG_COMPASS_CONFIG 40 // structs OK
|
||||
#define PG_MODE_ACTIVATION_PROFILE 41 // array needs to be made into struct
|
||||
//#define PG_SERVO_PROFILE 42
|
||||
#define PG_SERVO_PARAMS 42
|
||||
|
|
|
@ -778,34 +778,34 @@ static const clivalue_t valueTable[] = {
|
|||
{ "sdcard_dma", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &sdcardConfig()->useDma, .config.lookup = { TABLE_OFF_ON } },
|
||||
#endif
|
||||
#ifdef OSD
|
||||
{ "osd_units", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &osdProfile()->units, .config.lookup = { TABLE_UNIT } },
|
||||
{ "osd_units", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &osdConfig()->units, .config.lookup = { TABLE_UNIT } },
|
||||
|
||||
{ "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, &osdProfile()->rssi_alarm, .config.minmax = { 0, 100 } },
|
||||
{ "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, &osdProfile()->cap_alarm, .config.minmax = { 0, 20000 } },
|
||||
{ "osd_time_alarm", VAR_UINT16 | MASTER_VALUE, &osdProfile()->time_alarm, .config.minmax = { 0, 60 } },
|
||||
{ "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, &osdProfile()->alt_alarm, .config.minmax = { 0, 10000 } },
|
||||
{ "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, &osdConfig()->rssi_alarm, .config.minmax = { 0, 100 } },
|
||||
{ "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, &osdConfig()->cap_alarm, .config.minmax = { 0, 20000 } },
|
||||
{ "osd_time_alarm", VAR_UINT16 | MASTER_VALUE, &osdConfig()->time_alarm, .config.minmax = { 0, 60 } },
|
||||
{ "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, &osdConfig()->alt_alarm, .config.minmax = { 0, 10000 } },
|
||||
|
||||
{ "osd_vbat_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_MAIN_BATT_VOLTAGE], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_rssi_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_RSSI_VALUE], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_flytimer_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_FLYTIME], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_ontimer_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_ONTIME], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_flymode_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_FLYMODE], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_throttle_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_THROTTLE_POS], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_vtx_channel_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_VTX_CHANNEL], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_crosshairs", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_CROSSHAIRS], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_horizon_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_ARTIFICIAL_HORIZON], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_current_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_CURRENT_DRAW], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_mah_drawn_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_MAH_DRAWN], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_craft_name_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_CRAFT_NAME], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_gps_speed_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_GPS_SPEED], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_gps_sats_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_GPS_SATS], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_altitude_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_ALTITUDE], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_pid_roll_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_ROLL_PIDS], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_pid_pitch_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_PITCH_PIDS], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_pid_yaw_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_YAW_PIDS], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_power_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_POWER], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_pidrate_profile_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_PIDRATE_PROFILE], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_battery_warning_pos", VAR_UINT16 | MASTER_VALUE, &osdProfile()->item_pos[OSD_MAIN_BATT_WARNING], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_vbat_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_MAIN_BATT_VOLTAGE], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_rssi_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_RSSI_VALUE], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_flytimer_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_FLYTIME], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_ontimer_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_ONTIME], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_flymode_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_FLYMODE], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_throttle_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_THROTTLE_POS], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_vtx_channel_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_VTX_CHANNEL], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_crosshairs", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_CROSSHAIRS], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_horizon_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_ARTIFICIAL_HORIZON], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_current_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_CURRENT_DRAW], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_mah_drawn_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_MAH_DRAWN], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_craft_name_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_CRAFT_NAME], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_gps_speed_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_GPS_SPEED], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_gps_sats_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_GPS_SATS], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_altitude_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_ALTITUDE], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_pid_roll_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_ROLL_PIDS], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_pid_pitch_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_PITCH_PIDS], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_pid_yaw_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_YAW_PIDS], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_power_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_POWER], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_pidrate_profile_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_PIDRATE_PROFILE], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
{ "osd_battery_warning_pos", VAR_UINT16 | MASTER_VALUE, &osdConfig()->item_pos[OSD_MAIN_BATT_WARNING], .config.minmax = { 0, OSD_POSCFG_MAX } },
|
||||
#endif
|
||||
#ifdef USE_MAX7456
|
||||
{ "vcd_video_system", VAR_UINT8 | MASTER_VALUE, &vcdProfile()->video_system, .config.minmax = { 0, 2 } },
|
||||
|
@ -876,7 +876,7 @@ static adjustmentRange_t adjustmentRangesCopy[MAX_ADJUSTMENT_RANGE_COUNT];
|
|||
static ledStripConfig_t ledStripConfigCopy;
|
||||
#endif
|
||||
#ifdef OSD
|
||||
static osdConfig_t osdConfigCopy;
|
||||
static osd_profile_t osdConfigCopy;
|
||||
#endif
|
||||
static systemConfig_t systemConfigCopy;
|
||||
#ifdef BEEPER
|
||||
|
@ -1189,10 +1189,10 @@ static const cliCurrentAndDefaultConfig_t *getCurrentAndDefaultConfigs(pgn_t pgn
|
|||
ret.currentConfig = &controlRateProfilesCopy[0];
|
||||
ret.defaultConfig = controlRateProfiles(0);
|
||||
break;
|
||||
case PG_PID_PROFILE:
|
||||
/*!!TODO case PG_PID_PROFILE:
|
||||
ret.currentConfig = &pidProfileCopy[getConfigProfile()];
|
||||
ret.defaultConfig = pidProfile();
|
||||
break;
|
||||
break;*/
|
||||
case PG_RX_FAILSAFE_CHANNEL_CONFIG:
|
||||
ret.currentConfig = &rxFailsafeChannelConfigsCopy[0];
|
||||
ret.defaultConfig = rxFailsafeChannelConfigs(0);
|
||||
|
@ -1662,12 +1662,12 @@ static void cliAux(char *cmdline)
|
|||
const char *ptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
printAux(DUMP_MASTER, modeActivationProfile()->modeActivationConditions, NULL);
|
||||
printAux(DUMP_MASTER, modeActivationConditions(0), NULL);
|
||||
} else {
|
||||
ptr = cmdline;
|
||||
i = atoi(ptr++);
|
||||
if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
|
||||
modeActivationCondition_t *mac = &modeActivationProfile()->modeActivationConditions[i];
|
||||
modeActivationCondition_t *mac = modeActivationConditionsMutable(i);
|
||||
uint8_t validArgumentCount = 0;
|
||||
ptr = nextArg(ptr);
|
||||
if (ptr) {
|
||||
|
@ -1930,12 +1930,12 @@ static void cliAdjustmentRange(char *cmdline)
|
|||
const char *ptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
printAdjustmentRange(DUMP_MASTER, adjustmentProfile()->adjustmentRanges, NULL);
|
||||
printAdjustmentRange(DUMP_MASTER, adjustmentRanges(0), NULL);
|
||||
} else {
|
||||
ptr = cmdline;
|
||||
i = atoi(ptr++);
|
||||
if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
|
||||
adjustmentRange_t *ar = &adjustmentProfile()->adjustmentRanges[i];
|
||||
adjustmentRange_t *ar = adjustmentRangesMutable(i);
|
||||
uint8_t validArgumentCount = 0;
|
||||
|
||||
ptr = nextArg(ptr);
|
||||
|
@ -2354,7 +2354,7 @@ static void cliServo(char *cmdline)
|
|||
char *ptr;
|
||||
|
||||
if (isEmpty(cmdline)) {
|
||||
printServo(DUMP_MASTER, servoProfile()->servoConf, NULL);
|
||||
printServo(DUMP_MASTER, servoParams(0), NULL);
|
||||
} else {
|
||||
int validArgumentCount = 0;
|
||||
|
||||
|
@ -2393,7 +2393,7 @@ static void cliServo(char *cmdline)
|
|||
return;
|
||||
}
|
||||
|
||||
servo = &servoProfile()->servoConf[i];
|
||||
servo = servoParamsMutable(i);
|
||||
|
||||
if (
|
||||
arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX ||
|
||||
|
@ -2469,7 +2469,7 @@ static void printServoMix(uint8_t dumpMask, const master_t *defaultConfig)
|
|||
// print servo directions
|
||||
for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
const char *format = "smix reverse %d %d r\r\n";
|
||||
const servoParam_t *servoConf = &servoProfile()->servoConf[i];
|
||||
const servoParam_t *servoConf = servoParams(i);
|
||||
if (defaultConfig) {
|
||||
const servoParam_t *servoConfDefault = &defaultConfig->servoProfile.servoConf[i];
|
||||
bool equalsDefault = servoConf->reversedSources == servoConfDefault->reversedSources;
|
||||
|
@ -2503,7 +2503,7 @@ static void cliServoMix(char *cmdline)
|
|||
// erase custom mixer
|
||||
memset(masterConfig.customServoMixer, 0, sizeof(masterConfig.customServoMixer));
|
||||
for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||
servoProfile()->servoConf[i].reversedSources = 0;
|
||||
servoParamsMutable(i)->reversedSources = 0;
|
||||
}
|
||||
} else if (strncasecmp(cmdline, "load", 4) == 0) {
|
||||
const char *ptr = nextArg(cmdline);
|
||||
|
@ -2536,7 +2536,7 @@ static void cliServoMix(char *cmdline)
|
|||
for (uint32_t servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
|
||||
cliPrintf("%d", servoIndex);
|
||||
for (uint32_t inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
|
||||
cliPrintf("\t%s ", (servoProfile()->servoConf[servoIndex].reversedSources & (1 << inputSource)) ? "r" : "n");
|
||||
cliPrintf("\t%s ", (servoParams(servoIndex)->reversedSources & (1 << inputSource)) ? "r" : "n");
|
||||
cliPrintf("\r\n");
|
||||
}
|
||||
return;
|
||||
|
@ -2558,9 +2558,9 @@ static void cliServoMix(char *cmdline)
|
|||
&& args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT
|
||||
&& (*ptr == 'r' || *ptr == 'n')) {
|
||||
if (*ptr == 'r')
|
||||
servoProfile()->servoConf[args[SERVO]].reversedSources |= 1 << args[INPUT];
|
||||
servoParamsMutable(args[SERVO])->reversedSources |= 1 << args[INPUT];
|
||||
else
|
||||
servoProfile()->servoConf[args[SERVO]].reversedSources &= ~(1 << args[INPUT]);
|
||||
servoParamsMutable(args[SERVO])->reversedSources &= ~(1 << args[INPUT]);
|
||||
} else
|
||||
cliShowParseError();
|
||||
|
||||
|
@ -2740,8 +2740,6 @@ static void cliFlashRead(char *cmdline)
|
|||
{
|
||||
uint32_t address = atoi(cmdline);
|
||||
|
||||
uint8_t buffer[32];
|
||||
|
||||
const char *nextArg = strchr(cmdline, ' ');
|
||||
|
||||
if (!nextArg) {
|
||||
|
@ -2751,6 +2749,7 @@ static void cliFlashRead(char *cmdline)
|
|||
|
||||
cliPrintf("Reading %u bytes at %u:\r\n", length, address);
|
||||
|
||||
uint8_t buffer[32];
|
||||
while (length > 0) {
|
||||
int bytesRead = flashfsReadAbs(address, buffer, length < sizeof(buffer) ? length : sizeof(buffer));
|
||||
|
||||
|
@ -4005,7 +4004,7 @@ static void printConfig(char *cmdline, bool doDiff)
|
|||
|
||||
#ifdef USE_SERVOS
|
||||
cliPrintHashLine("servo");
|
||||
printServo(dumpMask, servoProfile()->servoConf, defaultConfig.servoProfile.servoConf);
|
||||
printServo(dumpMask, servoParams(0), defaultConfig.servoProfile.servoConf);
|
||||
|
||||
cliPrintHashLine("servo mix");
|
||||
// print custom servo mixer if exists
|
||||
|
@ -4040,10 +4039,10 @@ static void printConfig(char *cmdline, bool doDiff)
|
|||
#endif
|
||||
|
||||
cliPrintHashLine("aux");
|
||||
printAux(dumpMask, modeActivationProfile()->modeActivationConditions, defaultConfig.modeActivationProfile.modeActivationConditions);
|
||||
printAux(dumpMask, modeActivationConditions(0), defaultConfig.modeActivationProfile.modeActivationConditions);
|
||||
|
||||
cliPrintHashLine("adjrange");
|
||||
printAdjustmentRange(dumpMask, adjustmentProfile()->adjustmentRanges, defaultConfig.adjustmentProfile.adjustmentRanges);
|
||||
printAdjustmentRange(dumpMask, adjustmentRanges(0), defaultConfig.adjustmentProfile.adjustmentRanges);
|
||||
|
||||
cliPrintHashLine("rxrange");
|
||||
printRxRange(dumpMask, rxConfig()->channelRanges, defaultConfig.rxConfig.channelRanges);
|
||||
|
|
|
@ -887,7 +887,6 @@ void activateConfig(void)
|
|||
useAdjustmentConfig(¤tProfile->pidProfile);
|
||||
|
||||
#ifdef GPS
|
||||
gpsUseProfile(&masterConfig.gpsProfile);
|
||||
gpsUsePIDs(¤tProfile->pidProfile);
|
||||
#endif
|
||||
|
||||
|
|
|
@ -25,7 +25,9 @@
|
|||
#include "drivers/adc.h"
|
||||
#include "drivers/flash.h"
|
||||
#include "drivers/rx_pwm.h"
|
||||
#include "drivers/sdcard.h"
|
||||
#include "drivers/sound_beeper.h"
|
||||
#include "drivers/vcd.h"
|
||||
|
||||
#if FLASH_SIZE <= 128
|
||||
#define MAX_PROFILE_COUNT 2
|
||||
|
@ -77,6 +79,9 @@ PG_DECLARE(beeperDevConfig_t, beeperDevConfig);
|
|||
PG_DECLARE(flashConfig_t, flashConfig);
|
||||
PG_DECLARE(ppmConfig_t, ppmConfig);
|
||||
PG_DECLARE(pwmConfig_t, pwmConfig);
|
||||
PG_DECLARE(vcdProfile_t, vcdProfile);
|
||||
PG_DECLARE(sdcardConfig_t, sdcardConfig);
|
||||
|
||||
|
||||
/*typedef struct beeperConfig_s {
|
||||
uint32_t beeper_off_flags;
|
||||
|
|
|
@ -56,6 +56,7 @@
|
|||
#include "msp/msp_serial.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/motors.h"
|
||||
#include "io/servos.h"
|
||||
#include "io/serial.h"
|
||||
|
@ -69,12 +70,13 @@
|
|||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/altitudehold.h"
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/navigation.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
|
||||
|
||||
// June 2013 V2.2-dev
|
||||
|
|
|
@ -379,7 +379,7 @@ void init(void)
|
|||
|
||||
#ifdef USE_DASHBOARD
|
||||
if (feature(FEATURE_DASHBOARD)) {
|
||||
dashboardInit(rxConfig());
|
||||
dashboardInit();
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -450,14 +450,8 @@ void init(void)
|
|||
|
||||
#ifdef GPS
|
||||
if (feature(FEATURE_GPS)) {
|
||||
gpsInit(
|
||||
serialConfig(),
|
||||
gpsConfig()
|
||||
);
|
||||
navigationInit(
|
||||
gpsProfile(),
|
||||
¤tProfile->pidProfile
|
||||
);
|
||||
gpsInit();
|
||||
navigationInit(¤tProfile->pidProfile);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
|
@ -78,6 +78,7 @@
|
|||
#include "io/gps.h"
|
||||
#include "io/ledstrip.h"
|
||||
#include "io/motors.h"
|
||||
#include "io/osd.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/serial_4way.h"
|
||||
#include "io/servos.h"
|
||||
|
@ -1617,20 +1618,20 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
// set all the other settings
|
||||
if ((int8_t)addr == -1) {
|
||||
#ifdef USE_MAX7456
|
||||
vcdProfile()->video_system = sbufReadU8(src);
|
||||
vcdProfileMutable()->video_system = sbufReadU8(src);
|
||||
#else
|
||||
sbufReadU8(src); // Skip video system
|
||||
#endif
|
||||
osdProfile()->units = sbufReadU8(src);
|
||||
osdProfile()->rssi_alarm = sbufReadU8(src);
|
||||
osdProfile()->cap_alarm = sbufReadU16(src);
|
||||
osdProfile()->time_alarm = sbufReadU16(src);
|
||||
osdProfile()->alt_alarm = sbufReadU16(src);
|
||||
osdConfigMutable()->units = sbufReadU8(src);
|
||||
osdConfigMutable()->rssi_alarm = sbufReadU8(src);
|
||||
osdConfigMutable()->cap_alarm = sbufReadU16(src);
|
||||
osdConfigMutable()->time_alarm = sbufReadU16(src);
|
||||
osdConfigMutable()->alt_alarm = sbufReadU16(src);
|
||||
} else {
|
||||
// set a position setting
|
||||
const uint16_t pos = sbufReadU16(src);
|
||||
if (addr < OSD_ITEM_COUNT) {
|
||||
osdProfile()->item_pos[addr] = pos;
|
||||
osdConfigMutable()->item_pos[addr] = pos;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -75,17 +75,9 @@ static int16_t nav[2];
|
|||
static int16_t nav_rated[2]; // Adding a rate controller to the navigation to make it smoother
|
||||
navigationMode_e nav_mode = NAV_MODE_NONE; // Navigation mode
|
||||
|
||||
static gpsProfile_t *gpsProfile;
|
||||
|
||||
void gpsUseProfile(gpsProfile_t *gpsProfileToUse)
|
||||
{
|
||||
gpsProfile = gpsProfileToUse;
|
||||
}
|
||||
|
||||
// When using PWM input GPS usage reduces number of available channels by 2 - see pwm_common.c/pwmInit()
|
||||
void navigationInit(gpsProfile_t *initialGpsProfile, pidProfile_t *pidProfile)
|
||||
void navigationInit(pidProfile_t *pidProfile)
|
||||
{
|
||||
gpsUseProfile(initialGpsProfile);
|
||||
gpsUsePIDs(pidProfile);
|
||||
}
|
||||
|
||||
|
@ -166,7 +158,7 @@ static int32_t get_D(int32_t input, float *dt, PID *pid, PID_PARAM *pid_param)
|
|||
|
||||
// Low pass filter cut frequency for derivative calculation
|
||||
// Set to "1 / ( 2 * PI * gps_lpf )
|
||||
float pidFilter = (1.0f / (2.0f * M_PIf * (float)gpsProfile->gps_lpf));
|
||||
float pidFilter = (1.0f / (2.0f * M_PIf * (float)gpsProfile()->gps_lpf));
|
||||
// discrete low pass filter, cuts out the
|
||||
// high frequency noise that can drive the controller crazy
|
||||
pid->derivative = pid->last_derivative + (*dt / (pidFilter + *dt)) * (pid->derivative - pid->last_derivative);
|
||||
|
@ -330,13 +322,13 @@ void onGpsNewData(void)
|
|||
break;
|
||||
|
||||
case NAV_MODE_WP:
|
||||
speed = GPS_calc_desired_speed(gpsProfile->nav_speed_max, NAV_SLOW_NAV); // slow navigation
|
||||
speed = GPS_calc_desired_speed(gpsProfile()->nav_speed_max, NAV_SLOW_NAV); // slow navigation
|
||||
// use error as the desired rate towards the target
|
||||
// Desired output is in nav_lat and nav_lon where 1deg inclination is 100
|
||||
GPS_calc_nav_rate(speed);
|
||||
|
||||
// Tail control
|
||||
if (gpsProfile->nav_controls_heading) {
|
||||
if (gpsProfile()->nav_controls_heading) {
|
||||
if (NAV_TAIL_FIRST) {
|
||||
magHold = wrap_18000(nav_bearing - 18000) / 100;
|
||||
} else {
|
||||
|
@ -344,7 +336,7 @@ void onGpsNewData(void)
|
|||
}
|
||||
}
|
||||
// Are we there yet ?(within x meters of the destination)
|
||||
if ((wp_distance <= gpsProfile->gps_wp_radius) || check_missed_wp()) { // if yes switch to poshold mode
|
||||
if ((wp_distance <= gpsProfile()->gps_wp_radius) || check_missed_wp()) { // if yes switch to poshold mode
|
||||
nav_mode = NAV_MODE_POSHOLD;
|
||||
if (NAV_SET_TAKEOFF_HEADING) {
|
||||
magHold = nav_takeoff_bearing;
|
||||
|
@ -434,7 +426,7 @@ void GPS_set_next_wp(int32_t *lat, int32_t *lon)
|
|||
nav_bearing = target_bearing;
|
||||
GPS_calc_location_error(&GPS_WP[LAT], &GPS_WP[LON], &GPS_coord[LAT], &GPS_coord[LON]);
|
||||
original_target_bearing = target_bearing;
|
||||
waypoint_speed_gov = gpsProfile->nav_speed_min;
|
||||
waypoint_speed_gov = gpsProfile()->nav_speed_min;
|
||||
}
|
||||
|
||||
////////////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -613,7 +605,7 @@ static uint16_t GPS_calc_desired_speed(uint16_t max_speed, bool _slow)
|
|||
max_speed = MIN(max_speed, wp_distance / 2);
|
||||
} else {
|
||||
max_speed = MIN(max_speed, wp_distance);
|
||||
max_speed = MAX(max_speed, gpsProfile->nav_speed_min); // go at least 100cm/s
|
||||
max_speed = MAX(max_speed, gpsProfile()->nav_speed_min); // go at least 100cm/s
|
||||
}
|
||||
|
||||
// limit the ramp up of the speed
|
||||
|
@ -650,9 +642,9 @@ void updateGpsStateForHomeAndHoldMode(void)
|
|||
{
|
||||
float sin_yaw_y = sin_approx(DECIDEGREES_TO_DEGREES(attitude.values.yaw) * 0.0174532925f);
|
||||
float cos_yaw_x = cos_approx(DECIDEGREES_TO_DEGREES(attitude.values.yaw) * 0.0174532925f);
|
||||
if (gpsProfile->nav_slew_rate) {
|
||||
nav_rated[LON] += constrain(wrap_18000(nav[LON] - nav_rated[LON]), -gpsProfile->nav_slew_rate, gpsProfile->nav_slew_rate); // TODO check this on uint8
|
||||
nav_rated[LAT] += constrain(wrap_18000(nav[LAT] - nav_rated[LAT]), -gpsProfile->nav_slew_rate, gpsProfile->nav_slew_rate);
|
||||
if (gpsProfile()->nav_slew_rate) {
|
||||
nav_rated[LON] += constrain(wrap_18000(nav[LON] - nav_rated[LON]), -gpsProfile()->nav_slew_rate, gpsProfile()->nav_slew_rate); // TODO check this on uint8
|
||||
nav_rated[LAT] += constrain(wrap_18000(nav[LAT] - nav_rated[LAT]), -gpsProfile()->nav_slew_rate, gpsProfile()->nav_slew_rate);
|
||||
GPS_angle[AI_ROLL] = (nav_rated[LON] * cos_yaw_x - nav_rated[LAT] * sin_yaw_y) / 10;
|
||||
GPS_angle[AI_PITCH] = (nav_rated[LON] * sin_yaw_y + nav_rated[LAT] * cos_yaw_x) / 10;
|
||||
} else {
|
||||
|
@ -696,7 +688,7 @@ void updateGpsWaypointsAndMode(void)
|
|||
// process HOLD mode
|
||||
//
|
||||
|
||||
if (IS_RC_MODE_ACTIVE(BOXGPSHOLD) && areSticksInApModePosition(gpsProfile->ap_mode)) {
|
||||
if (IS_RC_MODE_ACTIVE(BOXGPSHOLD) && areSticksInApModePosition(gpsProfile()->ap_mode)) {
|
||||
if (!FLIGHT_MODE(GPS_HOLD_MODE)) {
|
||||
|
||||
// Transition to HOLD mode
|
||||
|
|
|
@ -36,6 +36,8 @@ typedef struct gpsProfile_s {
|
|||
uint16_t ap_mode; // Temporarily Disables GPS_HOLD_MODE to be able to make it possible to adjust the Hold-position when moving the sticks, creating a deadspan for GPS
|
||||
} gpsProfile_t;
|
||||
|
||||
PG_DECLARE(gpsProfile_t, gpsProfile);
|
||||
|
||||
extern int16_t GPS_angle[ANGLE_INDEX_COUNT]; // it's the angles that must be applied for GPS correction
|
||||
|
||||
extern int32_t GPS_home[2];
|
||||
|
@ -47,11 +49,10 @@ extern int16_t GPS_directionToHome; // direction to home or hol point in
|
|||
extern navigationMode_e nav_mode; // Navigation mode
|
||||
|
||||
struct pidProfile_s;
|
||||
void navigationInit(gpsProfile_t *initialGpsProfile, struct pidProfile_s *pidProfile);
|
||||
void navigationInit(struct pidProfile_s *pidProfile);
|
||||
void GPS_reset_home_position(void);
|
||||
void GPS_reset_nav(void);
|
||||
void GPS_set_next_wp(int32_t* lat, int32_t* lon);
|
||||
void gpsUseProfile(gpsProfile_t *gpsProfileToUse);
|
||||
void gpsUsePIDs(struct pidProfile_s *pidProfile);
|
||||
void updateGpsStateForHomeAndHoldMode(void);
|
||||
void updateGpsWaypointsAndMode(void);
|
||||
|
|
|
@ -84,7 +84,6 @@ controlRateConfig_t *getControlRateConfig(uint8_t profileIndex);
|
|||
static uint32_t nextDisplayUpdateAt = 0;
|
||||
static bool dashboardPresent = false;
|
||||
|
||||
static rxConfig_t *rxConfig;
|
||||
static displayPort_t *displayPort;
|
||||
|
||||
#define PAGE_TITLE_LINE_COUNT 1
|
||||
|
@ -701,7 +700,7 @@ void dashboardSetPage(pageId_e pageId)
|
|||
pageState.pageFlags |= PAGE_STATE_FLAG_FORCE_PAGE_CHANGE;
|
||||
}
|
||||
|
||||
void dashboardInit(rxConfig_t *rxConfigToUse)
|
||||
void dashboardInit(void)
|
||||
{
|
||||
delay(200);
|
||||
resetDisplay();
|
||||
|
@ -714,8 +713,6 @@ void dashboardInit(rxConfig_t *rxConfigToUse)
|
|||
}
|
||||
#endif
|
||||
|
||||
rxConfig = rxConfigToUse;
|
||||
|
||||
memset(&pageState, 0, sizeof(pageState));
|
||||
dashboardSetPage(PAGE_WELCOME);
|
||||
|
||||
|
|
|
@ -37,8 +37,7 @@ typedef enum {
|
|||
#endif
|
||||
} pageId_e;
|
||||
|
||||
struct rxConfig_s;
|
||||
void dashboardInit(struct rxConfig_s *intialRxConfig);
|
||||
void dashboardInit(void);
|
||||
void dashboardUpdate(timeUs_t currentTimeUs);
|
||||
|
||||
void dashboardShowFixedPage(pageId_e pageId);
|
||||
|
|
|
@ -29,6 +29,9 @@
|
|||
|
||||
#include "drivers/display.h"
|
||||
#include "drivers/max7456.h"
|
||||
#include "drivers/vcd.h"
|
||||
|
||||
#include "io/osd.h"
|
||||
|
||||
displayPort_t max7456DisplayPort; // Referenced from osd.c
|
||||
displayPortProfile_t *max7456DisplayPortProfile;
|
||||
|
|
|
@ -92,15 +92,12 @@ uint8_t GPS_svinfo_svid[GPS_SV_MAXSATS]; // Satellite ID
|
|||
uint8_t GPS_svinfo_quality[GPS_SV_MAXSATS]; // Bitfield Qualtity
|
||||
uint8_t GPS_svinfo_cno[GPS_SV_MAXSATS]; // Carrier to Noise Ratio (Signal Strength)
|
||||
|
||||
static gpsConfig_t *gpsConfig;
|
||||
|
||||
// GPS timeout for wrong baud rate/disconnection/etc in milliseconds (default 2.5second)
|
||||
#define GPS_TIMEOUT (2500)
|
||||
// How many entries in gpsInitData array below
|
||||
#define GPS_INIT_ENTRIES (GPS_BAUDRATE_MAX + 1)
|
||||
#define GPS_BAUDRATE_CHANGE_DELAY (200)
|
||||
|
||||
static serialConfig_t *serialConfig;
|
||||
static serialPort_t *gpsPort;
|
||||
|
||||
typedef struct gpsInitData_s {
|
||||
|
@ -207,19 +204,14 @@ static void gpsSetState(gpsState_e state)
|
|||
gpsData.messageState = GPS_MESSAGE_STATE_IDLE;
|
||||
}
|
||||
|
||||
void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig)
|
||||
void gpsInit(void)
|
||||
{
|
||||
serialConfig = initialSerialConfig;
|
||||
|
||||
|
||||
gpsData.baudrateIndex = 0;
|
||||
gpsData.errors = 0;
|
||||
gpsData.timeouts = 0;
|
||||
|
||||
memset(gpsPacketLog, 0x00, sizeof(gpsPacketLog));
|
||||
|
||||
gpsConfig = initialGpsConfig;
|
||||
|
||||
// init gpsData structure. if we're not actually enabled, don't bother doing anything else
|
||||
gpsSetState(GPS_UNKNOWN);
|
||||
|
||||
|
@ -242,7 +234,7 @@ void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig)
|
|||
portMode_t mode = MODE_RXTX;
|
||||
// only RX is needed for NMEA-style GPS
|
||||
#if !defined(COLIBRI_RACE) || !defined(LUX_RACE)
|
||||
if (gpsConfig->provider == GPS_NMEA)
|
||||
if (gpsConfig()->provider == GPS_NMEA)
|
||||
mode &= ~MODE_TX;
|
||||
#endif
|
||||
|
||||
|
@ -350,7 +342,7 @@ void gpsInitUblox(void)
|
|||
case GPS_CONFIGURE:
|
||||
|
||||
// Either use specific config file for GPS or let dynamically upload config
|
||||
if( gpsConfig->autoConfig == GPS_AUTOCONFIG_OFF ) {
|
||||
if( gpsConfig()->autoConfig == GPS_AUTOCONFIG_OFF ) {
|
||||
gpsSetState(GPS_RECEIVING_DATA);
|
||||
break;
|
||||
}
|
||||
|
@ -372,7 +364,7 @@ void gpsInitUblox(void)
|
|||
|
||||
if (gpsData.messageState == GPS_MESSAGE_STATE_SBAS) {
|
||||
if (gpsData.state_position < UBLOX_SBAS_MESSAGE_LENGTH) {
|
||||
serialWrite(gpsPort, ubloxSbas[gpsConfig->sbasMode].message[gpsData.state_position]);
|
||||
serialWrite(gpsPort, ubloxSbas[gpsConfig()->sbasMode].message[gpsData.state_position]);
|
||||
gpsData.state_position++;
|
||||
} else {
|
||||
gpsData.messageState++;
|
||||
|
@ -389,7 +381,7 @@ void gpsInitUblox(void)
|
|||
|
||||
void gpsInitHardware(void)
|
||||
{
|
||||
switch (gpsConfig->provider) {
|
||||
switch (gpsConfig()->provider) {
|
||||
case GPS_NMEA:
|
||||
gpsInitNmea();
|
||||
break;
|
||||
|
@ -429,7 +421,7 @@ void gpsUpdate(timeUs_t currentTimeUs)
|
|||
|
||||
case GPS_LOST_COMMUNICATION:
|
||||
gpsData.timeouts++;
|
||||
if (gpsConfig->autoBaud) {
|
||||
if (gpsConfig()->autoBaud) {
|
||||
// try another rate
|
||||
gpsData.baudrateIndex++;
|
||||
gpsData.baudrateIndex %= GPS_INIT_ENTRIES;
|
||||
|
@ -480,7 +472,7 @@ static void gpsNewData(uint16_t c)
|
|||
|
||||
bool gpsNewFrame(uint8_t c)
|
||||
{
|
||||
switch (gpsConfig->provider) {
|
||||
switch (gpsConfig()->provider) {
|
||||
case GPS_NMEA: // NMEA
|
||||
return gpsNewFrameNMEA(c);
|
||||
case GPS_UBLOX: // UBX binary
|
||||
|
|
|
@ -121,8 +121,7 @@ extern uint8_t GPS_svinfo_cno[16]; // Carrier to Noise Ratio (Signal Str
|
|||
#define GPS_DBHZ_MIN 0
|
||||
#define GPS_DBHZ_MAX 55
|
||||
|
||||
struct serialConfig_s;
|
||||
void gpsInit(struct serialConfig_s *serialConfig, gpsConfig_t *initialGpsConfig);
|
||||
void gpsInit(void);
|
||||
void gpsUpdate(timeUs_t currentTimeUs);
|
||||
bool gpsNewFrame(uint8_t c);
|
||||
struct serialPort_s;
|
||||
|
|
|
@ -32,6 +32,7 @@
|
|||
|
||||
#ifdef OSD
|
||||
|
||||
#include "blackbox/blackbox.h"
|
||||
#include "blackbox/blackbox_io.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
@ -39,6 +40,7 @@
|
|||
|
||||
#include "common/printf.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/typeconversion.h"
|
||||
#include "common/utils.h"
|
||||
|
||||
#include "config/config_profile.h"
|
||||
|
@ -59,6 +61,7 @@
|
|||
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
#include "io/flashfs.h"
|
||||
#include "io/gps.h"
|
||||
#include "io/osd.h"
|
||||
#include "io/vtx.h"
|
||||
|
||||
|
@ -66,6 +69,14 @@
|
|||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "flight/imu.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "sensors/barometer.h"
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#ifdef USE_HARDWARE_REVISION_DETECTION
|
||||
#include "hardware_revision.h"
|
||||
#endif
|
||||
|
@ -127,7 +138,7 @@ static displayPort_t *osdDisplayPort;
|
|||
*/
|
||||
static char osdGetAltitudeSymbol()
|
||||
{
|
||||
switch (osdProfile()->units) {
|
||||
switch (osdConfig()->units) {
|
||||
case OSD_UNIT_IMPERIAL:
|
||||
return 0xF;
|
||||
default:
|
||||
|
@ -141,7 +152,7 @@ static char osdGetAltitudeSymbol()
|
|||
*/
|
||||
static int32_t osdGetAltitude(int32_t alt)
|
||||
{
|
||||
switch (osdProfile()->units) {
|
||||
switch (osdConfig()->units) {
|
||||
case OSD_UNIT_IMPERIAL:
|
||||
return (alt * 328) / 100; // Convert to feet / 100
|
||||
default:
|
||||
|
@ -151,11 +162,11 @@ static int32_t osdGetAltitude(int32_t alt)
|
|||
|
||||
static void osdDrawSingleElement(uint8_t item)
|
||||
{
|
||||
if (!VISIBLE(osdProfile()->item_pos[item]) || BLINK(item))
|
||||
if (!VISIBLE(osdConfig()->item_pos[item]) || BLINK(item))
|
||||
return;
|
||||
|
||||
uint8_t elemPosX = OSD_X(osdProfile()->item_pos[item]);
|
||||
uint8_t elemPosY = OSD_Y(osdProfile()->item_pos[item]);
|
||||
uint8_t elemPosX = OSD_X(osdConfig()->item_pos[item]);
|
||||
uint8_t elemPosY = OSD_Y(osdConfig()->item_pos[item]);
|
||||
char buff[32];
|
||||
|
||||
switch(item) {
|
||||
|
@ -528,15 +539,13 @@ void osdInit(displayPort_t *osdDisplayPortToUse)
|
|||
|
||||
void osdUpdateAlarms(void)
|
||||
{
|
||||
osd_profile_t *pOsdProfile = &masterConfig.osdProfile;
|
||||
|
||||
// This is overdone?
|
||||
// uint16_t *itemPos = osdProfile()->item_pos;
|
||||
// uint16_t *itemPos = osdConfig()->item_pos;
|
||||
|
||||
int32_t alt = osdGetAltitude(baro.BaroAlt) / 100;
|
||||
statRssi = rssi * 100 / 1024;
|
||||
|
||||
if (statRssi < pOsdProfile->rssi_alarm)
|
||||
if (statRssi < osdConfig()->rssi_alarm)
|
||||
SET_BLINK(OSD_RSSI_VALUE);
|
||||
else
|
||||
CLR_BLINK(OSD_RSSI_VALUE);
|
||||
|
@ -554,17 +563,17 @@ void osdUpdateAlarms(void)
|
|||
else
|
||||
CLR_BLINK(OSD_GPS_SATS);
|
||||
|
||||
if (flyTime / 60 >= pOsdProfile->time_alarm && ARMING_FLAG(ARMED))
|
||||
if (flyTime / 60 >= osdConfig()->time_alarm && ARMING_FLAG(ARMED))
|
||||
SET_BLINK(OSD_FLYTIME);
|
||||
else
|
||||
CLR_BLINK(OSD_FLYTIME);
|
||||
|
||||
if (mAhDrawn >= pOsdProfile->cap_alarm)
|
||||
if (mAhDrawn >= osdConfig()->cap_alarm)
|
||||
SET_BLINK(OSD_MAH_DRAWN);
|
||||
else
|
||||
CLR_BLINK(OSD_MAH_DRAWN);
|
||||
|
||||
if (alt >= pOsdProfile->alt_alarm)
|
||||
if (alt >= osdConfig()->alt_alarm)
|
||||
SET_BLINK(OSD_ALTITUDE);
|
||||
else
|
||||
CLR_BLINK(OSD_ALTITUDE);
|
||||
|
|
Loading…
Reference in New Issue