Merge branch 'master' into development
This commit is contained in:
commit
b6d581bb73
|
@ -67,10 +67,10 @@ language: cpp
|
|||
compiler: clang
|
||||
|
||||
before_install:
|
||||
- curl --retry 10 --retry-max-time 120 -L "https://launchpad.net/gcc-arm-embedded/4.9/4.9-2015-q2-update/+download/gcc-arm-none-eabi-4_9-2015q2-20150609-linux.tar.bz2" | tar xfj -
|
||||
- curl --retry 10 --retry-max-time 120 -L "https://launchpad.net/gcc-arm-embedded/5.0/5-2016-q2-update/+download/gcc-arm-none-eabi-5_4-2016q2-20160622-linux.tar.bz2" | tar xfj -
|
||||
|
||||
install:
|
||||
- export PATH=$PATH:$PWD/gcc-arm-none-eabi-4_9-2015q2/bin
|
||||
- export PATH=$PATH:$PWD/gcc-arm-none-eabi-5_4-2016q2/bin
|
||||
|
||||
before_script: arm-none-eabi-gcc --version
|
||||
script: ./.travis.sh
|
||||
|
|
|
@ -113,11 +113,11 @@ static void resetControlRateConfig(controlRateConfig_t *controlRateConfig)
|
|||
{
|
||||
controlRateConfig->rcRate8 = 100;
|
||||
controlRateConfig->rcYawRate8 = 100;
|
||||
controlRateConfig->rcExpo8 = 10;
|
||||
controlRateConfig->rcExpo8 = 0;
|
||||
controlRateConfig->thrMid8 = 50;
|
||||
controlRateConfig->thrExpo8 = 0;
|
||||
controlRateConfig->dynThrPID = 20;
|
||||
controlRateConfig->rcYawExpo8 = 10;
|
||||
controlRateConfig->dynThrPID = 10;
|
||||
controlRateConfig->rcYawExpo8 = 0;
|
||||
controlRateConfig->tpa_breakpoint = 1650;
|
||||
|
||||
for (uint8_t axis = 0; axis < FLIGHT_DYNAMICS_INDEX_COUNT; axis++) {
|
||||
|
@ -133,7 +133,7 @@ static void resetPidProfile(pidProfile_t *pidProfile)
|
|||
pidProfile->I8[ROLL] = 40;
|
||||
pidProfile->D8[ROLL] = 20;
|
||||
pidProfile->P8[PITCH] = 60;
|
||||
pidProfile->I8[PITCH] = 60;
|
||||
pidProfile->I8[PITCH] = 65;
|
||||
pidProfile->D8[PITCH] = 22;
|
||||
pidProfile->P8[YAW] = 80;
|
||||
pidProfile->I8[YAW] = 45;
|
||||
|
@ -164,11 +164,11 @@ static void resetPidProfile(pidProfile_t *pidProfile)
|
|||
pidProfile->yawItermIgnoreRate = 32;
|
||||
pidProfile->dterm_filter_type = FILTER_BIQUAD;
|
||||
pidProfile->dterm_lpf_hz = 100; // filtering ON by default
|
||||
pidProfile->dterm_notch_hz = 0;
|
||||
pidProfile->dterm_notch_cutoff = 150;
|
||||
pidProfile->dterm_notch_hz = 260;
|
||||
pidProfile->dterm_notch_cutoff = 160;
|
||||
pidProfile->deltaMethod = DELTA_FROM_MEASUREMENT;
|
||||
pidProfile->vbatPidCompensation = 0;
|
||||
pidProfile->pidAtMinThrottle = PID_STABILISATION_OFF;
|
||||
pidProfile->pidAtMinThrottle = PID_STABILISATION_ON;
|
||||
|
||||
// Betaflight PID controller parameters
|
||||
pidProfile->ptermSetpointWeight = 75;
|
||||
|
@ -432,9 +432,9 @@ void createDefaultConfig(master_t *config)
|
|||
config->gyroConfig.gyroMovementCalibrationThreshold = 32;
|
||||
|
||||
// xxx_hardware: 0:default/autodetect, 1: disable
|
||||
config->mag_hardware = 0;
|
||||
config->mag_hardware = 1;
|
||||
|
||||
config->baro_hardware = 0;
|
||||
config->baro_hardware = 1;
|
||||
|
||||
resetBatteryConfig(&config->batteryConfig);
|
||||
|
||||
|
@ -513,8 +513,6 @@ void createDefaultConfig(master_t *config)
|
|||
|
||||
resetSerialConfig(&config->serialConfig);
|
||||
|
||||
config->emf_avoidance = 0; // TODO - needs removal
|
||||
|
||||
resetProfile(&config->profile[0]);
|
||||
|
||||
resetRollAndPitchTrims(&config->accelerometerTrims);
|
||||
|
@ -542,12 +540,12 @@ void createDefaultConfig(master_t *config)
|
|||
config->throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
|
||||
|
||||
// Failsafe Variables
|
||||
config->failsafeConfig.failsafe_delay = 10; // 1sec
|
||||
config->failsafeConfig.failsafe_off_delay = 10; // 1sec
|
||||
config->failsafeConfig.failsafe_throttle = 1000; // default throttle off.
|
||||
config->failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
|
||||
config->failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition
|
||||
config->failsafeConfig.failsafe_procedure = 0; // default full failsafe procedure is 0: auto-landing
|
||||
config->failsafeConfig.failsafe_delay = 10; // 1sec
|
||||
config->failsafeConfig.failsafe_off_delay = 10; // 1sec
|
||||
config->failsafeConfig.failsafe_throttle = 1000; // default throttle off.
|
||||
config->failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
|
||||
config->failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition
|
||||
config->failsafeConfig.failsafe_procedure = FAILSAFE_PROCEDURE_DROP_IT;// default full failsafe procedure is 0: auto-landing
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
// servos
|
||||
|
|
|
@ -25,7 +25,6 @@ typedef struct master_t {
|
|||
|
||||
uint8_t mixerMode;
|
||||
uint32_t enabledFeatures;
|
||||
uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band
|
||||
|
||||
// motor/esc/servo related stuff
|
||||
motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS];
|
||||
|
|
|
@ -817,8 +817,6 @@ void taskMainPidLoopCheck(void)
|
|||
static uint32_t previousTime;
|
||||
static bool runTaskMainSubprocesses;
|
||||
|
||||
const uint32_t currentDeltaTime = getTaskDeltaTime(TASK_SELF);
|
||||
|
||||
cycleTime = micros() - previousTime;
|
||||
previousTime = micros();
|
||||
|
||||
|
@ -828,30 +826,31 @@ void taskMainPidLoopCheck(void)
|
|||
}
|
||||
|
||||
const uint32_t startTime = micros();
|
||||
|
||||
while (true) {
|
||||
if (gyroSyncCheckUpdate(&gyro) || ((currentDeltaTime + (micros() - previousTime)) >= (gyro.targetLooptime + GYRO_WATCHDOG_DELAY))) {
|
||||
static uint8_t pidUpdateCountdown;
|
||||
|
||||
if (gyroSyncCheckUpdate(&gyro)) {
|
||||
if (debugMode == DEBUG_PIDLOOP) {debug[0] = micros() - startTime;} // time spent busy waiting
|
||||
if (runTaskMainSubprocesses) {
|
||||
subTaskMainSubprocesses();
|
||||
runTaskMainSubprocesses = false;
|
||||
}
|
||||
|
||||
gyroUpdate();
|
||||
|
||||
if (pidUpdateCountdown) {
|
||||
pidUpdateCountdown--;
|
||||
} else {
|
||||
pidUpdateCountdown = setPidUpdateCountDown();
|
||||
subTaskPidController();
|
||||
subTaskMotorUpdate();
|
||||
runTaskMainSubprocesses = true;
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
static uint8_t pidUpdateCountdown;
|
||||
|
||||
if (runTaskMainSubprocesses) {
|
||||
subTaskMainSubprocesses();
|
||||
runTaskMainSubprocesses = false;
|
||||
}
|
||||
|
||||
gyroUpdate();
|
||||
|
||||
if (pidUpdateCountdown) {
|
||||
pidUpdateCountdown--;
|
||||
} else {
|
||||
pidUpdateCountdown = setPidUpdateCountDown();
|
||||
subTaskPidController();
|
||||
subTaskMotorUpdate();
|
||||
runTaskMainSubprocesses = true;
|
||||
}
|
||||
}
|
||||
|
||||
void taskUpdateAccelerometer(void)
|
||||
|
|
|
@ -519,6 +519,10 @@ static const char * const lookupTableLowpassType[] = {
|
|||
"NORMAL", "HIGH"
|
||||
};
|
||||
|
||||
static const char * const lookupTableFailsafe[] = {
|
||||
"AUTO-LAND", "DROP"
|
||||
};
|
||||
|
||||
typedef struct lookupTableEntry_s {
|
||||
const char * const *values;
|
||||
const uint8_t valueCount;
|
||||
|
@ -557,6 +561,7 @@ typedef enum {
|
|||
TABLE_DELTA_METHOD,
|
||||
TABLE_RC_INTERPOLATION,
|
||||
TABLE_LOWPASS_TYPE,
|
||||
TABLE_FAILSAFE,
|
||||
#ifdef OSD
|
||||
TABLE_OSD,
|
||||
#endif
|
||||
|
@ -595,6 +600,7 @@ static const lookupTableEntry_t lookupTables[] = {
|
|||
{ lookupTableDeltaMethod, sizeof(lookupTableDeltaMethod) / sizeof(char *) },
|
||||
{ lookupTableRcInterpolation, sizeof(lookupTableRcInterpolation) / sizeof(char *) },
|
||||
{ lookupTableLowpassType, sizeof(lookupTableLowpassType) / sizeof(char *) },
|
||||
{ lookupTableFailsafe, sizeof(lookupTableFailsafe) / sizeof(char *) },
|
||||
#ifdef OSD
|
||||
{ lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) },
|
||||
#endif
|
||||
|
@ -648,7 +654,6 @@ typedef struct {
|
|||
} clivalue_t;
|
||||
|
||||
const clivalue_t valueTable[] = {
|
||||
// { "emf_avoidance", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.emf_avoidance, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, .config.minmax = { 1200, 1700 } },
|
||||
{ "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
||||
{ "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
|
||||
|
@ -810,7 +815,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX } },
|
||||
{ "failsafe_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_kill_switch, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle_low_delay, .config.minmax = { 0, 300 } },
|
||||
{ "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_procedure, .config.lookup = { TABLE_OFF_ON } },
|
||||
{ "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_procedure, .config.lookup = { TABLE_FAILSAFE } },
|
||||
|
||||
{ "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
|
||||
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
|
||||
|
@ -854,8 +859,8 @@ const clivalue_t valueTable[] = {
|
|||
{ "yaw_rate_accel_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawRateAccelLimit, .config.minmax = {0, 1000 } },
|
||||
{ "rate_accel_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rateAccelLimit, .config.minmax = {0, 1000 } },
|
||||
|
||||
{ "accumulation_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } },
|
||||
{ "yaw_accumulation_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } },
|
||||
{ "accum_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } },
|
||||
{ "yaw_accum_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } },
|
||||
{ "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } },
|
||||
{ "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_process_denom, .config.minmax = { 1, 8 } },
|
||||
|
||||
|
@ -2769,13 +2774,6 @@ static void printConfig(char *cmdline, bool doDiff)
|
|||
#endif
|
||||
printRxRange(dumpMask, &defaultConfig);
|
||||
|
||||
#ifdef USE_SERVOS
|
||||
#ifndef CLI_MINIMAL_VERBOSITY
|
||||
cliPrint("\r\n# servo\r\n");
|
||||
#endif
|
||||
printServo(dumpMask, &defaultConfig);
|
||||
#endif
|
||||
|
||||
#ifdef VTX
|
||||
#ifndef CLI_MINIMAL_VERBOSITY
|
||||
cliPrint("\r\n# vtx\r\n");
|
||||
|
|
|
@ -678,7 +678,7 @@ void main_init(void)
|
|||
|
||||
/* Setup scheduler */
|
||||
schedulerInit();
|
||||
rescheduleTask(TASK_GYROPID, gyro.targetLooptime);
|
||||
rescheduleTask(TASK_GYROPID, gyro.targetLooptime + 5); // Add a littlebit of extra time to reduce busy wait
|
||||
setTaskEnabled(TASK_GYROPID, true);
|
||||
|
||||
if (sensors(SENSOR_ACC)) {
|
||||
|
|
Loading…
Reference in New Issue