Merge pull request #2504 from martinbudden/bf_pg_configs9

Added PG config definitions 9
This commit is contained in:
Martin Budden 2017-02-27 09:25:55 +00:00 committed by GitHub
commit 331cd22d24
9 changed files with 63 additions and 37 deletions

View File

@ -92,7 +92,9 @@
#define PG_PWM_CONFIG 508
#define PG_SERIAL_PIN_CONFIG 509
#define PG_ADC_CONFIG 510
#define PG_BETAFLIGHT_END 510
#define PG_SDCARD_CONFIG 511
#define PG_DISPLAY_PORT_MSP_CONFIG 512
#define PG_BETAFLIGHT_END 512
// OSD configuration (subject to change)

View File

@ -660,7 +660,7 @@ static const clivalue_t valueTable[] = {
{ "hott_alarm_int", VAR_UINT8 | MASTER_VALUE, &telemetryConfig()->hottAlarmSoundInterval, .config.minmax = { 0, 120 } },
{ "pid_in_tlm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &telemetryConfig()->pidValuesAsTelemetry, .config.lookup = {TABLE_OFF_ON } },
#if defined(TELEMETRY_IBUS)
{ "ibus_report_cell_voltage", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &ibusTelemetryConfig()->report_cell_voltage, .config.lookup = { TABLE_OFF_ON } },
{ "ibus_report_cell_voltage", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &telemetryConfig()->report_cell_voltage, .config.lookup = { TABLE_OFF_ON } },
#endif
#endif

View File

@ -142,6 +142,18 @@ PG_REGISTER_WITH_RESET_TEMPLATE(flashConfig_t, flashConfig, PG_FLASH_CONFIG, 0);
PG_RESET_TEMPLATE(flashConfig_t, flashConfig,
.csTag = FLASH_CONFIG_CSTAG
);
#endif // USE_FLASH_FS
#ifdef USE_SDCARD
PG_REGISTER_WITH_RESET_TEMPLATE(sdcardConfig_t, sdcardConfig, PG_SDCARD_CONFIG, 0);
#if defined(SDCARD_DMA_CHANNEL_TX)
#define SDCARD_CONFIG_USE_DMA true
#else
#define SDCARD_CONFIG_USE_DMA false
#endif
PG_RESET_TEMPLATE(sdcardConfig_t, sdcardConfig,
.useDma = SDCARD_CONFIG_USE_DMA
);
#endif
#ifndef USE_PARAMETER_GROUPS
@ -239,7 +251,6 @@ void resetProfile(profile_t *profile)
{
resetPidProfile(&profile->pidProfile);
}
#endif
#ifdef GPS
void resetGpsProfile(gpsProfile_t *gpsProfile)
@ -254,7 +265,6 @@ void resetGpsProfile(gpsProfile_t *gpsProfile)
}
#endif
#ifndef USE_PARAMETER_GROUPS
#ifdef BARO
void resetBarometerConfig(barometerConfig_t *barometerConfig)
{
@ -353,6 +363,7 @@ void resetSonarConfig(sonarConfig_t *sonarConfig)
}
#endif
#ifndef USE_PARAMETER_GROUPS
#ifdef USE_SDCARD
void resetsdcardConfig(sdcardConfig_t *sdcardConfig)
{
@ -362,7 +373,8 @@ void resetsdcardConfig(sdcardConfig_t *sdcardConfig)
sdcardConfig->useDma = false;
#endif
}
#endif
#endif // USE_SDCARD
#endif // USE_PARAMETER_GROUPS
#ifdef USE_ADC
#ifdef USE_PARAMETER_GROUPS
@ -392,7 +404,7 @@ void resetAdcConfig(adcConfig_t *adcConfig)
#endif
}
#endif
#endif // USE_ADC
#ifndef USE_PARAMETER_GROUPS
@ -738,11 +750,13 @@ void resetMax7456Config(vcdProfile_t *pVcdProfile)
}
#endif
#ifndef USE_PARAMETER_GROUPS
void resetDisplayPortProfile(displayPortProfile_t *pDisplayPortProfile)
{
pDisplayPortProfile->colAdjust = 0;
pDisplayPortProfile->rowAdjust = 0;
}
#endif // USE_PARAMETER_GROUPS
#ifdef USE_PARAMETER_GROUPS
void pgResetFn_statusLedConfig(statusLedConfig_t *statusLedConfig)
@ -942,12 +956,12 @@ void createDefaultConfig(master_t *config)
resetSonarConfig(&config->sonarConfig);
#endif
#ifndef USE_PARAMETER_GROUPS
#ifdef USE_SDCARD
intFeatureSet(FEATURE_SDCARD, featuresPtr);
resetsdcardConfig(&config->sdcardConfig);
#endif
#ifndef USE_PARAMETER_GROUPS
#ifdef SERIALRX_PROVIDER
config->rxConfig.serialrx_provider = SERIALRX_PROVIDER;
#else
@ -1001,7 +1015,6 @@ void createDefaultConfig(master_t *config)
#ifdef LED_STRIP
resetLedStripConfig(&config->ledStripConfig);
#endif
#endif
#ifdef GPS
// gps/nav stuff
@ -1011,7 +1024,6 @@ void createDefaultConfig(master_t *config)
config->gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
#endif
#ifndef USE_PARAMETER_GROUPS
resetSerialPinConfig(&config->serialPinConfig);
resetSerialConfig(&config->serialConfig);
@ -1075,8 +1087,10 @@ void createDefaultConfig(master_t *config)
config->channelForwardingConfig.startChannel = AUX1;
#endif
#ifndef USE_PARAMETER_GROUPS
#ifdef GPS
resetGpsProfile(&config->gpsProfile);
#endif
#endif
// custom mixer. clear by defaults.

View File

@ -18,12 +18,12 @@
#include <stdbool.h>
#include <stdint.h>
#include <ctype.h>
#include <string.h>
#include <math.h>
#include "platform.h"
#ifdef GPS
#include "build/debug.h"
#include "common/axis.h"
@ -37,6 +37,7 @@
#include "drivers/system.h"
#include "fc/config.h"
#include "fc/fc_core.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
@ -55,9 +56,17 @@
#include "sensors/sensors.h"
extern int16_t magHold;
PG_REGISTER_WITH_RESET_TEMPLATE(gpsProfile_t, gpsProfile, PG_NAVIGATION_CONFIG, 0);
#ifdef GPS
PG_RESET_TEMPLATE(gpsProfile_t, gpsProfile,
.gps_wp_radius = 200,
.gps_lpf = 20,
.nav_slew_rate = 30,
.nav_controls_heading = 1,
.nav_speed_min = 100,
.nav_speed_max = 300,
.ap_mode = 40
);
bool areSticksInApModePosition(uint16_t ap_mode);

View File

@ -86,7 +86,6 @@ typedef struct pidProfile_s {
float rateAccelLimit; // accel limiter roll/pitch deg/sec/ms
} pidProfile_t;
//PG_DECLARE_PROFILE(pidProfile_t, pidProfile);
#if FLASH_SIZE <= 128
#define MAX_PROFILE_COUNT 2
#else

View File

@ -26,17 +26,21 @@
#include "common/utils.h"
#include "config/config_master.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "drivers/display.h"
#include "drivers/system.h"
#include "fc/fc_msp.h"
#include "io/displayport_msp.h"
#include "msp/msp_protocol.h"
#include "msp/msp_serial.h"
#include "io/displayport_msp.h"
// no template required since defaults are zero
PG_REGISTER(displayPortProfile_t, displayPortProfileMsp, PG_DISPLAY_PORT_MSP_CONFIG, 0);
static displayPort_t mspDisplayPort;

View File

@ -183,6 +183,15 @@ typedef enum {
gpsData_t gpsData;
PG_REGISTER_WITH_RESET_TEMPLATE(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 0);
PG_RESET_TEMPLATE(gpsConfig_t, gpsConfig,
.provider = GPS_NMEA,
.sbasMode = SBAS_AUTO,
.autoConfig = GPS_AUTOCONFIG_ON,
.autoBaud = GPS_AUTOBAUD_OFF
);
static void shiftPacketLog(void)
{
uint32_t i;

View File

@ -24,35 +24,37 @@
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include "platform.h"
#include "common/utils.h"
#if defined(TELEMETRY) && defined(TELEMETRY_IBUS)
#include "common/axis.h"
#include "common/utils.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "common/axis.h"
#include "drivers/system.h"
#include "drivers/sensor.h"
#include "drivers/accgyro.h"
#include "drivers/serial.h"
#include "fc/rc_controls.h"
#include "io/serial.h"
#include "sensors/sensors.h"
#include "sensors/acceleration.h"
#include "sensors/battery.h"
#include "sensors/barometer.h"
#include "io/serial.h"
#include "fc/rc_controls.h"
#include "scheduler/scheduler.h"
#include "telemetry/telemetry.h"
#include "telemetry/ibus.h"
#include "telemetry/telemetry.h"
/*
* iBus Telemetry is a half-duplex serial protocol. It shares 1 line for
@ -160,13 +162,6 @@
*
*/
/*
PG_REGISTER_WITH_RESET_TEMPLATE(ibusTelemetryConfig_t, ibusTelemetryConfig, PG_IBUS_TELEMETRY_CONFIG, 0);
PG_RESET_TEMPLATE(ibusTelemetryConfig_t, ibusTelemetryConfig,
.report_cell_voltage = false,
);
*/
#define IBUS_TASK_PERIOD_US (1000)
@ -290,7 +285,7 @@ static void dispatchMeasurementReply(ibusAddress_t address)
switch (sensorAddressTypeLookup[address - ibusBaseAddress]) {
case IBUS_SENSOR_TYPE_EXTERNAL_VOLTAGE:
value = getVbat() * 10;
if (ibusTelemetryConfig()->report_cell_voltage) {
if (telemetryConfig()->report_cell_voltage) {
value /= batteryCellCount;
}
sendIbusMeasurement(address, value);

View File

@ -17,12 +17,6 @@
#pragma once
typedef struct ibusTelemetryConfig_s {
uint8_t report_cell_voltage; // report vbatt divided with cellcount
} ibusTelemetryConfig_t;
PG_DECLARE(ibusTelemetryConfig_t, ibusTelemetryConfig);
void initIbusTelemetry(void);
void handleIbusTelemetry(void);