Merge branch 'master' into bfdev-configurable-baro

This commit is contained in:
jflyper 2017-07-19 18:18:23 +09:00 committed by GitHub
commit 363cfae650
15 changed files with 69 additions and 36 deletions

View File

@ -55,9 +55,9 @@ typedef struct gyroDev_s {
extiCallbackRec_t exti;
busDevice_t bus;
float scale; // scalefactor
int16_t gyroADCRaw[XYZ_AXIS_COUNT];
int32_t gyroZero[XYZ_AXIS_COUNT];
int32_t gyroADC[XYZ_AXIS_COUNT]; // gyro data after calibration and alignment
int16_t gyroADCRaw[XYZ_AXIS_COUNT];
int16_t temperature;
uint8_t lpf;
gyroRateKHz_e gyroRateKHz;

View File

@ -206,7 +206,7 @@ bool mpuGyroRead(gyroDev_t *gyro)
{
uint8_t data[6];
const bool ack = gyro->mpuConfiguration.readFn(&gyro->bus, gyro->mpuConfiguration.gyroReadXRegister, 6, data);
const bool ack = gyro->mpuConfiguration.readFn(&gyro->bus, MPU_RA_GYRO_XOUT_H, 6, data);
if (!ack) {
return false;
}
@ -253,7 +253,6 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
sensor = mpu6000SpiDetect(&gyro->bus);
if (sensor != MPU_NONE) {
gyro->mpuDetectionResult.sensor = sensor;
gyro->mpuConfiguration.gyroReadXRegister = MPU_RA_GYRO_XOUT_H;
gyro->mpuConfiguration.readFn = spiReadRegisterBuffer;
gyro->mpuConfiguration.writeFn = spiWriteRegister;
return true;
@ -271,7 +270,6 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
// some targets using MPU_9250_SPI, ICM_20608_SPI or ICM_20602_SPI state sensor is MPU_65xx_SPI
if (sensor != MPU_NONE) {
gyro->mpuDetectionResult.sensor = sensor;
gyro->mpuConfiguration.gyroReadXRegister = MPU_RA_GYRO_XOUT_H;
gyro->mpuConfiguration.readFn = spiReadRegisterBuffer;
gyro->mpuConfiguration.writeFn = spiWriteRegister;
return true;
@ -288,7 +286,6 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
sensor = mpu9250SpiDetect(&gyro->bus);
if (sensor != MPU_NONE) {
gyro->mpuDetectionResult.sensor = sensor;
gyro->mpuConfiguration.gyroReadXRegister = MPU_RA_GYRO_XOUT_H;
gyro->mpuConfiguration.readFn = spiReadRegisterBuffer;
gyro->mpuConfiguration.writeFn = spiWriteRegister;
gyro->mpuConfiguration.resetFn = mpu9250SpiResetGyro;
@ -306,7 +303,6 @@ static bool detectSPISensorsAndUpdateDetectionResult(gyroDev_t *gyro)
sensor = icm20689SpiDetect(&gyro->bus);
if (sensor != MPU_NONE) {
gyro->mpuDetectionResult.sensor = sensor;
gyro->mpuConfiguration.gyroReadXRegister = MPU_RA_GYRO_XOUT_H;
gyro->mpuConfiguration.readFn = spiReadRegisterBuffer;
gyro->mpuConfiguration.writeFn = spiWriteRegister;
return true;
@ -354,15 +350,12 @@ void mpuDetect(gyroDev_t *gyro)
return;
}
gyro->mpuConfiguration.gyroReadXRegister = MPU_RA_GYRO_XOUT_H;
// If an MPU3050 is connected sig will contain 0.
uint8_t inquiryResult;
ack = mpuReadRegisterI2C(&gyro->bus, MPU_RA_WHO_AM_I_LEGACY, 1, &inquiryResult);
inquiryResult &= MPU_INQUIRY_MASK;
if (ack && inquiryResult == MPUx0x0_WHO_AM_I_CONST) {
gyro->mpuDetectionResult.sensor = MPU_3050;
gyro->mpuConfiguration.gyroReadXRegister = MPU3050_GYRO_OUT;
return;
}

View File

@ -135,7 +135,6 @@ typedef struct mpuConfiguration_s {
mpuReadRegisterFnPtr readFn;
mpuWriteRegisterFnPtr writeFn;
mpuResetFnPtr resetFn;
uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each
} mpuConfiguration_t;
enum gyro_fsr_e {

View File

@ -64,6 +64,22 @@ static void mpu3050Init(gyroDev_t *gyro)
gyro->mpuConfiguration.writeFn(&gyro->bus, MPU3050_PWR_MGM, MPU3050_CLK_SEL_PLL_GX);
}
static bool mpu3050GyroRead(gyroDev_t *gyro)
{
uint8_t data[6];
const bool ack = gyro->mpuConfiguration.readFn(&gyro->bus, MPU3050_GYRO_OUT, 6, data);
if (!ack) {
return false;
}
gyro->gyroADCRaw[X] = (int16_t)((data[0] << 8) | data[1]);
gyro->gyroADCRaw[Y] = (int16_t)((data[2] << 8) | data[3]);
gyro->gyroADCRaw[Z] = (int16_t)((data[4] << 8) | data[5]);
return true;
}
static bool mpu3050ReadTemperature(gyroDev_t *gyro, int16_t *tempData)
{
uint8_t buf[2];
@ -82,7 +98,7 @@ bool mpu3050Detect(gyroDev_t *gyro)
return false;
}
gyro->initFn = mpu3050Init;
gyro->readFn = mpuGyroRead;
gyro->readFn = mpu3050GyroRead;
gyro->temperatureFn = mpu3050ReadTemperature;
// 16.4 dps/lsb scalefactor

View File

@ -3032,9 +3032,15 @@ const cliResourceValue_t resourceTable[] = {
#ifdef USE_ESCSERIAL
{ OWNER_ESCSERIAL, PG_ESCSERIAL_CONFIG, offsetof(escSerialConfig_t, ioTag), 0 },
#endif
#ifdef CAMERA_CONTROL
#ifdef USE_CAMERA_CONTROL
{ OWNER_CAMERA_CONTROL, PG_CAMERA_CONTROL_CONFIG, offsetof(cameraControlConfig_t, ioTag), 0 },
#endif
#ifdef USE_ADC
{ OWNER_ADC_BATT, PG_ADC_CONFIG, offsetof(adcConfig_t, vbat.ioTag), 0 },
{ OWNER_ADC_RSSI, PG_ADC_CONFIG, offsetof(adcConfig_t, rssi.ioTag), 0 },
{ OWNER_ADC_CURR, PG_ADC_CONFIG, offsetof(adcConfig_t, current.ioTag), 0 },
{ OWNER_ADC_EXT, PG_ADC_CONFIG, offsetof(adcConfig_t, external1.ioTag), 0 },
#endif
#ifdef BARO
{ OWNER_BARO_CS, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_spi_csn), 0 },
#endif

View File

@ -470,7 +470,7 @@ void init(void)
rtc6705IOInit();
#endif
#ifdef CAMERA_CONTROL
#ifdef USE_CAMERA_CONTROL
cameraControlInit();
#endif

View File

@ -704,9 +704,14 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
break;
}
case MSP_VOLTAGE_METERS:
case MSP_VOLTAGE_METERS: {
// write out id and voltage meter values, once for each meter we support
for (int i = 0; i < supportedVoltageMeterCount; i++) {
uint8_t count = supportedVoltageMeterCount;
#ifndef USE_OSD_SLAVE
count = supportedVoltageMeterCount - (VOLTAGE_METER_ID_ESC_COUNT - getMotorCount());
#endif
for (int i = 0; i < count; i++) {
voltageMeter_t meter;
uint8_t id = (uint8_t)voltageMeterIds[i];
@ -716,10 +721,15 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
sbufWriteU8(dst, (uint8_t)constrain(meter.filtered, 0, 255));
}
break;
}
case MSP_CURRENT_METERS:
case MSP_CURRENT_METERS: {
// write out id and current meter values, once for each meter we support
for (int i = 0; i < supportedCurrentMeterCount; i++) {
uint8_t count = supportedVoltageMeterCount;
#ifndef USE_OSD_SLAVE
count = supportedVoltageMeterCount - (VOLTAGE_METER_ID_ESC_COUNT - getMotorCount());
#endif
for (int i = 0; i < count; i++) {
currentMeter_t meter;
uint8_t id = (uint8_t)currentMeterIds[i];
@ -730,6 +740,7 @@ static bool mspCommonProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProce
sbufWriteU16(dst, (uint16_t)constrain(meter.amperage * 10, 0, 0xFFFF)); // send amperage in 0.001 A steps (mA). Negative range is truncated to zero
}
break;
}
case MSP_VOLTAGE_METER_CONFIG:
// by using a sensor type and a sub-frame length it's possible to configure any type of voltage meter,
@ -2131,12 +2142,12 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
#endif
case MSP_SET_VOLTAGE_METER_CONFIG: {
int id = sbufReadU8(src);
int8_t id = sbufReadU8(src);
//
// find and configure an ADC voltage sensor
//
int voltageSensorADCIndex;
int8_t voltageSensorADCIndex;
for (voltageSensorADCIndex = 0; voltageSensorADCIndex < MAX_VOLTAGE_SENSOR_ADC; voltageSensorADCIndex++) {
if (id == voltageMeterADCtoIDMap[voltageSensorADCIndex]) {
break;
@ -2149,7 +2160,9 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
voltageSensorADCConfigMutable(voltageSensorADCIndex)->vbatresdivmultiplier = sbufReadU8(src);
} else {
// if we had any other types of voltage sensor to configure, this is where we'd do it.
return -1;
sbufReadU8(src);
sbufReadU8(src);
sbufReadU8(src);
}
break;
}
@ -2168,11 +2181,11 @@ static mspResult_e mspCommonProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
currentSensorVirtualConfigMutable()->offset = sbufReadU16(src);
break;
#endif
default:
return -1;
sbufReadU16(src);
sbufReadU16(src);
break;
}
break;
}

View File

@ -61,8 +61,8 @@ PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig,
.failsafe_delay = 10, // 1sec
.failsafe_off_delay = 10, // 1sec
.failsafe_throttle = 1000, // default throttle off.
.failsafe_kill_switch = 0, // default failsafe switch action is identical to rc link loss
.failsafe_throttle_low_delay = 100, // default throttle low delay for "just disarm" on failsafe condition
.failsafe_kill_switch = 0, // default failsafe switch action is identical to rc link loss
.failsafe_procedure = FAILSAFE_PROCEDURE_DROP_IT // default full failsafe procedure is 0: auto-landing
);

View File

@ -33,8 +33,8 @@ typedef struct failsafeConfig_s {
uint8_t failsafe_delay; // Guard time for failsafe activation after signal lost. 1 step = 0.1sec - 1sec in example (10)
uint8_t failsafe_off_delay; // Time for Landing before motors stop in 0.1sec. 1 step = 0.1sec - 20sec in example (200)
uint16_t failsafe_throttle; // Throttle level used for landing - specify value between 1000..2000 (pwm pulse width for slightly below hover). center throttle = 1500.
uint8_t failsafe_kill_switch; // failsafe switch action is 0: identical to rc link loss, 1: disarms instantly
uint16_t failsafe_throttle_low_delay; // Time throttle stick must have been below 'min_check' to "JustDisarm" instead of "full failsafe procedure".
uint8_t failsafe_kill_switch; // failsafe switch action is 0: identical to rc link loss, 1: disarms instantly
uint8_t failsafe_procedure; // selected full failsafe procedure is 0: auto-landing, 1: Drop it
} failsafeConfig_t;

View File

@ -90,11 +90,11 @@ void resetPidProfile(pidProfile_t *pidProfile)
.pidSumLimit = PIDSUM_LIMIT,
.pidSumLimitYaw = PIDSUM_LIMIT_YAW,
.yaw_lpf_hz = 0,
.itermWindupPointPercent = 50,
.dterm_filter_type = FILTER_BIQUAD,
.dterm_lpf_hz = 100, // filtering ON by default
.dterm_notch_hz = 260,
.dterm_notch_cutoff = 160,
.dterm_filter_type = FILTER_BIQUAD,
.itermWindupPointPercent = 50,
.vbatPidCompensation = 0,
.pidAtMinThrottle = PID_STABILISATION_ON,
.levelAngleLimit = 55,

View File

@ -74,11 +74,11 @@ typedef struct pid8_s {
typedef struct pidProfile_s {
pid8_t pid[PID_ITEM_COUNT];
uint8_t dterm_filter_type; // Filter selection for dterm
uint16_t dterm_lpf_hz; // Delta Filter in hz
uint16_t yaw_lpf_hz; // Additional yaw filter when yaw axis too noisy
uint16_t dterm_lpf_hz; // Delta Filter in hz
uint16_t dterm_notch_hz; // Biquad dterm notch hz
uint16_t dterm_notch_cutoff; // Biquad dterm notch low cutoff
uint8_t dterm_filter_type; // Filter selection for dterm
uint8_t itermWindupPointPercent; // Experimental ITerm windup threshold, percent motor saturation
uint16_t pidSumLimit;
uint16_t pidSumLimitYaw;

View File

@ -131,9 +131,9 @@ typedef struct osdConfig_s {
bool enabled_stats[OSD_STAT_COUNT];
// Alarms
uint8_t rssi_alarm;
uint16_t cap_alarm;
uint16_t alt_alarm;
uint8_t rssi_alarm;
osd_unit_e units;

View File

@ -60,6 +60,8 @@ typedef enum {
#define MAX_VOLTAGE_SENSOR_ADC 1 // VBAT - some boards have external, 12V, 9V and 5V meters.
#endif
#define VOLTAGE_METER_ID_ESC_COUNT 12
typedef enum {
VOLTAGE_SENSOR_ADC_VBAT = 0,
VOLTAGE_SENSOR_ADC_12V = 1,

View File

@ -46,11 +46,11 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
#if defined(OMNIBUSF4SD)
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S5_OUT
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S6_OUT
DEF_TIM(TIM4, CH1, PB6, TIM_USE_LED, TIMER_OUTPUT_STANDARD, 0), // LED strip for F4 V2 / F4-Pro-0X and later (RCD_CS for F4)
#else
DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_LED, TIMER_OUTPUT_STANDARD, 0), // S5_OUT
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S6_OUT
#endif
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_STANDARD, 0), // S6_OUT
DEF_TIM(TIM1, CH2, PA9, TIM_USE_NONE, TIMER_OUTPUT_NONE, 0), // UART1_TX
DEF_TIM(TIM1, CH3, PA10, TIM_USE_NONE, TIMER_OUTPUT_NONE, 0), // UART1_RX
};

View File

@ -207,14 +207,18 @@
#define USE_ADC
#define CURRENT_METER_ADC_PIN PC1 // Direct from CRNT pad (part of onboard sensor for Pro)
#define VBAT_ADC_PIN PC2 // 11:1 (10K + 1K) divider
#ifdef DYSF4PRO
#define RSSI_ADC_PIN PC3 // Direct from RSSI pad
#else
#define RSSI_ADC_PIN PA0 // Direct from RSSI pad
#endif
#define TRANSPONDER
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES (FEATURE_OSD)
#define AVOID_UART1_FOR_PWM_PPM
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13)))
@ -223,8 +227,8 @@
#define TARGET_IO_PORTD BIT(2)
#ifdef OMNIBUSF4SD
#define USABLE_TIMER_CHANNEL_COUNT 13
#define USABLE_TIMER_CHANNEL_COUNT 15
#else
#define USABLE_TIMER_CHANNEL_COUNT 12
#define USABLE_TIMER_CHANNEL_COUNT 14
#endif
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9))