Merge pull request #999 from AlienWiiBF/AF_custom_config

Target custom config update
This commit is contained in:
borisbstyle 2016-08-14 09:21:25 +02:00 committed by GitHub
commit dd50de3b12
10 changed files with 99 additions and 105 deletions

View File

@ -90,7 +90,7 @@
#endif
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse);
void targetConfiguration(void);
void targetConfiguration(master_t *config);
#if !defined(FLASH_SIZE)
#error "Flash size not defined for target. (specify in KB)"
@ -689,12 +689,7 @@ void createDefaultConfig(master_t *config)
#endif
#if defined(TARGET_CONFIG)
// Don't look at target specific config settings when getting default
// values for a CLI diff. This is suboptimal, but it doesn't break the
// public API
if (config == &masterConfig) {
targetConfiguration();
}
targetConfiguration(config);
#endif

View File

@ -70,26 +70,26 @@
#include "config/config_master.h"
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void)
void targetConfiguration(master_t *config)
{
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
masterConfig.motor_pwm_rate = 32000;
masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0;
masterConfig.profile[0].pidProfile.P8[ROLL] = 90;
masterConfig.profile[0].pidProfile.I8[ROLL] = 44;
masterConfig.profile[0].pidProfile.D8[ROLL] = 60;
masterConfig.profile[0].pidProfile.P8[PITCH] = 90;
masterConfig.profile[0].pidProfile.I8[PITCH] = 44;
masterConfig.profile[0].pidProfile.D8[PITCH] = 60;
config->rxConfig.spektrum_sat_bind = 5;
config->rxConfig.spektrum_sat_bind_autoreset = 1;
config->motor_pwm_rate = 32000;
config->failsafeConfig.failsafe_delay = 2;
config->failsafeConfig.failsafe_off_delay = 0;
config->profile[0].pidProfile.P8[ROLL] = 90;
config->profile[0].pidProfile.I8[ROLL] = 44;
config->profile[0].pidProfile.D8[ROLL] = 60;
config->profile[0].pidProfile.P8[PITCH] = 90;
config->profile[0].pidProfile.I8[PITCH] = 44;
config->profile[0].pidProfile.D8[PITCH] = 60;
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif
config->customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
config->customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
config->customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
config->customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
config->customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
config->customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
config->customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
config->customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif
}

View File

@ -76,28 +76,28 @@
#include "config/config_master.h"
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void) {
masterConfig.mag_hardware = MAG_NONE; // disabled by default
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
masterConfig.motor_pwm_rate = 32000;
masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0;
masterConfig.gyro_sync_denom = 2;
masterConfig.pid_process_denom = 1;
masterConfig.profile[0].pidProfile.P8[ROLL] = 90;
masterConfig.profile[0].pidProfile.I8[ROLL] = 44;
masterConfig.profile[0].pidProfile.D8[ROLL] = 60;
masterConfig.profile[0].pidProfile.P8[PITCH] = 90;
masterConfig.profile[0].pidProfile.I8[PITCH] = 44;
masterConfig.profile[0].pidProfile.D8[PITCH] = 60;
void targetConfiguration(master_t *config) {
config->mag_hardware = MAG_NONE; // disabled by default
config->rxConfig.spektrum_sat_bind = 5;
config->rxConfig.spektrum_sat_bind_autoreset = 1;
config->motor_pwm_rate = 32000;
config->failsafeConfig.failsafe_delay = 2;
config->failsafeConfig.failsafe_off_delay = 0;
config->gyro_sync_denom = 2;
config->pid_process_denom = 1;
config->profile[0].pidProfile.P8[ROLL] = 90;
config->profile[0].pidProfile.I8[ROLL] = 44;
config->profile[0].pidProfile.D8[ROLL] = 60;
config->profile[0].pidProfile.P8[PITCH] = 90;
config->profile[0].pidProfile.I8[PITCH] = 44;
config->profile[0].pidProfile.D8[PITCH] = 60;
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif
config->customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
config->customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
config->customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
config->customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
config->customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
config->customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
config->customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
config->customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif
}

View File

@ -76,28 +76,28 @@
#include "config/config_master.h"
// alternative defaults settings for AlienFlight targets
void targetConfiguration(void) {
masterConfig.mag_hardware = MAG_NONE; // disabled by default
masterConfig.rxConfig.spektrum_sat_bind = 5;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
masterConfig.motor_pwm_rate = 32000;
masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0;
masterConfig.gyro_sync_denom = 1;
masterConfig.pid_process_denom = 1;
masterConfig.profile[0].pidProfile.P8[ROLL] = 90;
masterConfig.profile[0].pidProfile.I8[ROLL] = 44;
masterConfig.profile[0].pidProfile.D8[ROLL] = 60;
masterConfig.profile[0].pidProfile.P8[PITCH] = 90;
masterConfig.profile[0].pidProfile.I8[PITCH] = 44;
masterConfig.profile[0].pidProfile.D8[PITCH] = 60;
void targetConfiguration(master_t *config) {
config->mag_hardware = MAG_NONE; // disabled by default
config->rxConfig.spektrum_sat_bind = 5;
config->rxConfig.spektrum_sat_bind_autoreset = 1;
config->motor_pwm_rate = 32000;
config->failsafeConfig.failsafe_delay = 2;
config->failsafeConfig.failsafe_off_delay = 0;
config->gyro_sync_denom = 1;
config->pid_process_denom = 1;
config->profile[0].pidProfile.P8[ROLL] = 90;
config->profile[0].pidProfile.I8[ROLL] = 44;
config->profile[0].pidProfile.D8[ROLL] = 60;
config->profile[0].pidProfile.P8[PITCH] = 90;
config->profile[0].pidProfile.I8[PITCH] = 44;
config->profile[0].pidProfile.D8[PITCH] = 60;
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif
config->customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
config->customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
config->customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
config->customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
config->customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
config->customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
config->customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
config->customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif
}

View File

@ -78,10 +78,10 @@
#include "hardware_revision.h"
// alternative defaults settings for BlueJayF4 targets
void targetConfiguration(void)
void targetConfiguration(master_t *config)
{
if (hardwareRevision == BJF4_REV1 || hardwareRevision == BJF4_REV2) {
masterConfig.sensorAlignmentConfig.gyro_align = CW180_DEG;
masterConfig.sensorAlignmentConfig.acc_align = CW180_DEG;
config->sensorAlignmentConfig.gyro_align = CW180_DEG;
config->sensorAlignmentConfig.acc_align = CW180_DEG;
}
}

View File

@ -79,21 +79,20 @@
#include "config/config_master.h"
// alternative defaults settings for Colibri/Gemini targets
void targetConfiguration(void)
void targetConfiguration(master_t *config)
{
masterConfig.mixerMode = MIXER_HEX6X;
masterConfig.rxConfig.serialrx_provider = 2;
featureSet(FEATURE_RX_SERIAL);
config->mixerMode = MIXER_HEX6X;
config->rxConfig.serialrx_provider = 2;
masterConfig.escAndServoConfig.minthrottle = 1070;
masterConfig.escAndServoConfig.maxthrottle = 2000;
config->escAndServoConfig.minthrottle = 1070;
config->escAndServoConfig.maxthrottle = 2000;
masterConfig.boardAlignment.pitchDegrees = 10;
//masterConfig.rcControlsConfig.deadband = 10;
//masterConfig.rcControlsConfig.yaw_deadband = 10;
masterConfig.mag_hardware = 1;
config->boardAlignment.pitchDegrees = 10;
//config->rcControlsConfig.deadband = 10;
//config->rcControlsConfig.yaw_deadband = 10;
config->mag_hardware = 1;
masterConfig.profile[0].controlRateProfile[0].dynThrPID = 45;
masterConfig.profile[0].controlRateProfile[0].tpa_breakpoint = 1700;
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
config->profile[0].controlRateProfile[0].dynThrPID = 45;
config->profile[0].controlRateProfile[0].tpa_breakpoint = 1700;
config->serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
}

View File

@ -135,7 +135,7 @@
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL)
#define DEFAULT_FEATURES FEATURE_BLACKBOX
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -76,9 +76,9 @@
#include "config/config_master.h"
// alternative defaults settings for COLIBRI RACE targets
void targetConfiguration(void) {
masterConfig.escAndServoConfig.minthrottle = 1025;
masterConfig.escAndServoConfig.maxthrottle = 1980;
masterConfig.batteryConfig.vbatmaxcellvoltage = 45;
masterConfig.batteryConfig.vbatmincellvoltage = 30;
void targetConfiguration(master_t *config) {
config->escAndServoConfig.minthrottle = 1025;
config->escAndServoConfig.maxthrottle = 1980;
config->batteryConfig.vbatmaxcellvoltage = 45;
config->batteryConfig.vbatmincellvoltage = 30;
}

View File

@ -76,11 +76,11 @@
#include "config/config_master.h"
// alternative defaults settings for FURYF4 targets
void targetConfiguration(void) {
masterConfig.mag_hardware = MAG_NONE; // disabled by default
masterConfig.motor_pwm_rate = 32000;
masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0;
masterConfig.gyro_sync_denom = 1;
masterConfig.pid_process_denom = 1;
void targetConfiguration(master_t *config) {
config->mag_hardware = MAG_NONE; // disabled by default
config->motor_pwm_rate = 32000;
config->failsafeConfig.failsafe_delay = 2;
config->failsafeConfig.failsafe_off_delay = 0;
config->gyro_sync_denom = 1;
config->pid_process_denom = 1;
}

View File

@ -76,7 +76,7 @@
#include "config/config_master.h"
// Motolab target supports 2 different type of boards Tornado / Cyclone.
void targetConfiguration(void) {
masterConfig.gyro_sync_denom = 4;
masterConfig.pid_process_denom = 1;
void targetConfiguration(master_t *config) {
config->gyro_sync_denom = 4;
config->pid_process_denom = 1;
}