mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-23 08:15:30 +03:00
commit
36de2bbc23
12 changed files with 214 additions and 303 deletions
|
@ -850,7 +850,7 @@ void startBlackbox(void)
|
||||||
*/
|
*/
|
||||||
blackboxBuildConditionCache();
|
blackboxBuildConditionCache();
|
||||||
|
|
||||||
blackboxModeActivationConditionPresent = isModeActivationConditionPresent(currentProfile->modeActivationConditions, BOXBLACKBOX);
|
blackboxModeActivationConditionPresent = isModeActivationConditionPresent(masterConfig.modeActivationConditions, BOXBLACKBOX);
|
||||||
|
|
||||||
blackboxIteration = 0;
|
blackboxIteration = 0;
|
||||||
blackboxPFrameIndex = 0;
|
blackboxPFrameIndex = 0;
|
||||||
|
@ -1136,7 +1136,7 @@ static bool blackboxWriteSysinfo()
|
||||||
blackboxPrintfHeaderLine("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
|
blackboxPrintfHeaderLine("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
|
||||||
break;
|
break;
|
||||||
case 4:
|
case 4:
|
||||||
blackboxPrintfHeaderLine("rcRate:%d", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8);
|
blackboxPrintfHeaderLine("rcRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile.rcRate8);
|
||||||
break;
|
break;
|
||||||
case 5:
|
case 5:
|
||||||
blackboxPrintfHeaderLine("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle);
|
blackboxPrintfHeaderLine("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle);
|
||||||
|
|
|
@ -134,7 +134,7 @@ static uint32_t activeFeaturesLatch = 0;
|
||||||
static uint8_t currentControlRateProfileIndex = 0;
|
static uint8_t currentControlRateProfileIndex = 0;
|
||||||
controlRateConfig_t *currentControlRateProfile;
|
controlRateConfig_t *currentControlRateProfile;
|
||||||
|
|
||||||
static const uint8_t EEPROM_CONF_VERSION = 120;
|
static const uint8_t EEPROM_CONF_VERSION = 121;
|
||||||
|
|
||||||
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
||||||
{
|
{
|
||||||
|
@ -348,6 +348,7 @@ uint8_t getCurrentProfile(void)
|
||||||
static void setProfile(uint8_t profileIndex)
|
static void setProfile(uint8_t profileIndex)
|
||||||
{
|
{
|
||||||
currentProfile = &masterConfig.profile[profileIndex];
|
currentProfile = &masterConfig.profile[profileIndex];
|
||||||
|
currentControlRateProfile = ¤tProfile->controlRateProfile;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t getCurrentControlRateProfile(void)
|
uint8_t getCurrentControlRateProfile(void)
|
||||||
|
@ -356,13 +357,7 @@ uint8_t getCurrentControlRateProfile(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
controlRateConfig_t *getControlRateConfig(uint8_t profileIndex) {
|
controlRateConfig_t *getControlRateConfig(uint8_t profileIndex) {
|
||||||
return &masterConfig.controlRateProfiles[profileIndex];
|
return &masterConfig.profile[profileIndex].controlRateProfile;
|
||||||
}
|
|
||||||
|
|
||||||
static void setControlRateProfile(uint8_t profileIndex)
|
|
||||||
{
|
|
||||||
currentControlRateProfileIndex = profileIndex;
|
|
||||||
currentControlRateProfile = &masterConfig.controlRateProfiles[profileIndex];
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t getCurrentMinthrottle(void)
|
uint16_t getCurrentMinthrottle(void)
|
||||||
|
@ -378,7 +373,6 @@ static void resetConf(void)
|
||||||
// Clear all configuration
|
// Clear all configuration
|
||||||
memset(&masterConfig, 0, sizeof(master_t));
|
memset(&masterConfig, 0, sizeof(master_t));
|
||||||
setProfile(0);
|
setProfile(0);
|
||||||
setControlRateProfile(0);
|
|
||||||
|
|
||||||
masterConfig.beeper_off.flags = BEEPER_OFF_FLAGS_MIN;
|
masterConfig.beeper_off.flags = BEEPER_OFF_FLAGS_MIN;
|
||||||
masterConfig.version = EEPROM_CONF_VERSION;
|
masterConfig.version = EEPROM_CONF_VERSION;
|
||||||
|
@ -491,29 +485,26 @@ static void resetConf(void)
|
||||||
|
|
||||||
resetPidProfile(¤tProfile->pidProfile);
|
resetPidProfile(¤tProfile->pidProfile);
|
||||||
|
|
||||||
resetControlRateConfig(&masterConfig.controlRateProfiles[0]);
|
resetControlRateConfig(&masterConfig.profile[0].controlRateProfile);
|
||||||
|
|
||||||
// for (i = 0; i < CHECKBOXITEMS; i++)
|
resetRollAndPitchTrims(&masterConfig.accelerometerTrims);
|
||||||
// cfg.activate[i] = 0;
|
|
||||||
|
|
||||||
resetRollAndPitchTrims(¤tProfile->accelerometerTrims);
|
masterConfig.mag_declination = 0;
|
||||||
|
masterConfig.acc_lpf_hz = 20;
|
||||||
|
masterConfig.accz_lpf_cutoff = 5.0f;
|
||||||
|
masterConfig.accDeadband.xy = 40;
|
||||||
|
masterConfig.accDeadband.z = 40;
|
||||||
|
masterConfig.acc_unarmedcal = 1;
|
||||||
|
|
||||||
currentProfile->mag_declination = 0;
|
resetBarometerConfig(&masterConfig.barometerConfig);
|
||||||
currentProfile->acc_lpf_hz = 20;
|
|
||||||
currentProfile->accz_lpf_cutoff = 5.0f;
|
|
||||||
currentProfile->accDeadband.xy = 40;
|
|
||||||
currentProfile->accDeadband.z = 40;
|
|
||||||
currentProfile->acc_unarmedcal = 1;
|
|
||||||
|
|
||||||
resetBarometerConfig(¤tProfile->barometerConfig);
|
|
||||||
|
|
||||||
// Radio
|
// Radio
|
||||||
parseRcChannels("AETR1234", &masterConfig.rxConfig);
|
parseRcChannels("AETR1234", &masterConfig.rxConfig);
|
||||||
|
|
||||||
resetRcControlsConfig(¤tProfile->rcControlsConfig);
|
resetRcControlsConfig(&masterConfig.rcControlsConfig);
|
||||||
|
|
||||||
currentProfile->throttle_correction_value = 0; // could 10 with althold or 40 for fpv
|
masterConfig.throttle_correction_value = 0; // could 10 with althold or 40 for fpv
|
||||||
currentProfile->throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
|
masterConfig.throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
|
||||||
|
|
||||||
// Failsafe Variables
|
// Failsafe Variables
|
||||||
masterConfig.failsafeConfig.failsafe_delay = 10; // 1sec
|
masterConfig.failsafeConfig.failsafe_delay = 10; // 1sec
|
||||||
|
@ -525,21 +516,21 @@ static void resetConf(void)
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
// servos
|
// servos
|
||||||
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||||
currentProfile->servoConf[i].min = DEFAULT_SERVO_MIN;
|
masterConfig.servoConf[i].min = DEFAULT_SERVO_MIN;
|
||||||
currentProfile->servoConf[i].max = DEFAULT_SERVO_MAX;
|
masterConfig.servoConf[i].max = DEFAULT_SERVO_MAX;
|
||||||
currentProfile->servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
|
masterConfig.servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
|
||||||
currentProfile->servoConf[i].rate = 100;
|
masterConfig.servoConf[i].rate = 100;
|
||||||
currentProfile->servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
|
masterConfig.servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
|
||||||
currentProfile->servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
|
masterConfig.servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
|
||||||
currentProfile->servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
|
masterConfig.servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
|
||||||
}
|
}
|
||||||
|
|
||||||
// gimbal
|
// gimbal
|
||||||
currentProfile->gimbalConfig.mode = GIMBAL_MODE_NORMAL;
|
masterConfig.gimbalConfig.mode = GIMBAL_MODE_NORMAL;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
resetGpsProfile(¤tProfile->gpsProfile);
|
resetGpsProfile(&masterConfig.gpsProfile);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// custom mixer. clear by defaults.
|
// custom mixer. clear by defaults.
|
||||||
|
@ -590,7 +581,7 @@ static void resetConf(void)
|
||||||
currentControlRateProfile->rates[FD_YAW] = 90;
|
currentControlRateProfile->rates[FD_YAW] = 90;
|
||||||
currentControlRateProfile->dynThrPID = 30;
|
currentControlRateProfile->dynThrPID = 30;
|
||||||
currentControlRateProfile->tpa_breakpoint = 1500;
|
currentControlRateProfile->tpa_breakpoint = 1500;
|
||||||
currentProfile->rcControlsConfig.deadband = 10;
|
masterConfig.rcControlsConfig.deadband = 10;
|
||||||
|
|
||||||
masterConfig.escAndServoConfig.minthrottle = 1025;
|
masterConfig.escAndServoConfig.minthrottle = 1025;
|
||||||
masterConfig.escAndServoConfig.maxthrottle = 1980;
|
masterConfig.escAndServoConfig.maxthrottle = 1980;
|
||||||
|
@ -709,14 +700,6 @@ static void resetConf(void)
|
||||||
memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));
|
memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));
|
||||||
}
|
}
|
||||||
|
|
||||||
// copy first control rate config into remaining profile
|
|
||||||
for (i = 1; i < MAX_CONTROL_RATE_PROFILE_COUNT; i++) {
|
|
||||||
memcpy(&masterConfig.controlRateProfiles[i], currentControlRateProfile, sizeof(controlRateConfig_t));
|
|
||||||
}
|
|
||||||
|
|
||||||
for (i = 1; i < MAX_PROFILE_COUNT; i++) {
|
|
||||||
masterConfig.profile[i].defaultRateProfileIndex = i % MAX_CONTROL_RATE_PROFILE_COUNT;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static uint8_t calculateChecksum(const uint8_t *data, uint32_t length)
|
static uint8_t calculateChecksum(const uint8_t *data, uint32_t length)
|
||||||
|
@ -767,7 +750,7 @@ void activateConfig(void)
|
||||||
resetAdjustmentStates();
|
resetAdjustmentStates();
|
||||||
|
|
||||||
useRcControlsConfig(
|
useRcControlsConfig(
|
||||||
currentProfile->modeActivationConditions,
|
masterConfig.modeActivationConditions,
|
||||||
&masterConfig.escAndServoConfig,
|
&masterConfig.escAndServoConfig,
|
||||||
¤tProfile->pidProfile
|
¤tProfile->pidProfile
|
||||||
);
|
);
|
||||||
|
@ -781,7 +764,7 @@ void activateConfig(void)
|
||||||
pidSetController(currentProfile->pidProfile.pidController);
|
pidSetController(currentProfile->pidProfile.pidController);
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
gpsUseProfile(¤tProfile->gpsProfile);
|
gpsUseProfile(&masterConfig.gpsProfile);
|
||||||
gpsUsePIDs(¤tProfile->pidProfile);
|
gpsUsePIDs(¤tProfile->pidProfile);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -790,8 +773,8 @@ void activateConfig(void)
|
||||||
|
|
||||||
mixerUseConfigs(
|
mixerUseConfigs(
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
currentProfile->servoConf,
|
masterConfig.servoConf,
|
||||||
¤tProfile->gimbalConfig,
|
&masterConfig.gimbalConfig,
|
||||||
#endif
|
#endif
|
||||||
&masterConfig.flight3DConfig,
|
&masterConfig.flight3DConfig,
|
||||||
&masterConfig.escAndServoConfig,
|
&masterConfig.escAndServoConfig,
|
||||||
|
@ -802,27 +785,27 @@ void activateConfig(void)
|
||||||
|
|
||||||
imuRuntimeConfig.dcm_kp = masterConfig.dcm_kp / 10000.0f;
|
imuRuntimeConfig.dcm_kp = masterConfig.dcm_kp / 10000.0f;
|
||||||
imuRuntimeConfig.dcm_ki = masterConfig.dcm_ki / 10000.0f;
|
imuRuntimeConfig.dcm_ki = masterConfig.dcm_ki / 10000.0f;
|
||||||
imuRuntimeConfig.acc_cut_hz = currentProfile->acc_lpf_hz;
|
imuRuntimeConfig.acc_cut_hz = masterConfig.acc_lpf_hz;
|
||||||
imuRuntimeConfig.acc_unarmedcal = currentProfile->acc_unarmedcal;
|
imuRuntimeConfig.acc_unarmedcal = masterConfig.acc_unarmedcal;
|
||||||
imuRuntimeConfig.small_angle = masterConfig.small_angle;
|
imuRuntimeConfig.small_angle = masterConfig.small_angle;
|
||||||
|
|
||||||
imuConfigure(
|
imuConfigure(
|
||||||
&imuRuntimeConfig,
|
&imuRuntimeConfig,
|
||||||
¤tProfile->pidProfile,
|
¤tProfile->pidProfile,
|
||||||
¤tProfile->accDeadband,
|
&masterConfig.accDeadband,
|
||||||
currentProfile->accz_lpf_cutoff,
|
masterConfig.accz_lpf_cutoff,
|
||||||
currentProfile->throttle_correction_angle
|
masterConfig.throttle_correction_angle
|
||||||
);
|
);
|
||||||
|
|
||||||
configureAltitudeHold(
|
configureAltitudeHold(
|
||||||
¤tProfile->pidProfile,
|
¤tProfile->pidProfile,
|
||||||
¤tProfile->barometerConfig,
|
&masterConfig.barometerConfig,
|
||||||
¤tProfile->rcControlsConfig,
|
&masterConfig.rcControlsConfig,
|
||||||
&masterConfig.escAndServoConfig
|
&masterConfig.escAndServoConfig
|
||||||
);
|
);
|
||||||
|
|
||||||
#ifdef BARO
|
#ifdef BARO
|
||||||
useBarometerConfig(¤tProfile->barometerConfig);
|
useBarometerConfig(&masterConfig.barometerConfig);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -953,11 +936,6 @@ void readEEPROM(void)
|
||||||
|
|
||||||
setProfile(masterConfig.current_profile_index);
|
setProfile(masterConfig.current_profile_index);
|
||||||
|
|
||||||
if (currentProfile->defaultRateProfileIndex > MAX_CONTROL_RATE_PROFILE_COUNT - 1) // sanity check
|
|
||||||
currentProfile->defaultRateProfileIndex = 0;
|
|
||||||
|
|
||||||
setControlRateProfile(currentProfile->defaultRateProfileIndex);
|
|
||||||
|
|
||||||
validateAndFixConfig();
|
validateAndFixConfig();
|
||||||
activateConfig();
|
activateConfig();
|
||||||
|
|
||||||
|
@ -1056,15 +1034,6 @@ void changeProfile(uint8_t profileIndex)
|
||||||
beeperConfirmationBeeps(profileIndex + 1);
|
beeperConfirmationBeeps(profileIndex + 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
void changeControlRateProfile(uint8_t profileIndex)
|
|
||||||
{
|
|
||||||
if (profileIndex > MAX_CONTROL_RATE_PROFILE_COUNT) {
|
|
||||||
profileIndex = MAX_CONTROL_RATE_PROFILE_COUNT - 1;
|
|
||||||
}
|
|
||||||
setControlRateProfile(profileIndex);
|
|
||||||
activateControlRateConfig();
|
|
||||||
}
|
|
||||||
|
|
||||||
void handleOneshotFeatureChangeOnRestart(void)
|
void handleOneshotFeatureChangeOnRestart(void)
|
||||||
{
|
{
|
||||||
// Shutdown PWM on all motors prior to soft restart
|
// Shutdown PWM on all motors prior to soft restart
|
||||||
|
|
|
@ -17,8 +17,7 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#define MAX_PROFILE_COUNT 3
|
#define MAX_PROFILE_COUNT 2
|
||||||
#define MAX_CONTROL_RATE_PROFILE_COUNT 3
|
|
||||||
#define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500
|
#define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
@ -68,7 +67,6 @@ uint8_t getCurrentProfile(void);
|
||||||
void changeProfile(uint8_t profileIndex);
|
void changeProfile(uint8_t profileIndex);
|
||||||
|
|
||||||
uint8_t getCurrentControlRateProfile(void);
|
uint8_t getCurrentControlRateProfile(void);
|
||||||
void changeControlRateProfile(uint8_t profileIndex);
|
|
||||||
|
|
||||||
bool canSoftwareSerialBeUsed(void);
|
bool canSoftwareSerialBeUsed(void);
|
||||||
|
|
||||||
|
|
|
@ -27,23 +27,30 @@ typedef struct master_t {
|
||||||
uint32_t enabledFeatures;
|
uint32_t enabledFeatures;
|
||||||
uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band
|
uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band
|
||||||
|
|
||||||
motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS];
|
beeperOffConditions_t beeper_off;
|
||||||
#ifdef USE_SERVOS
|
|
||||||
servoMixer_t customServoMixer[MAX_SERVO_RULES];
|
|
||||||
#endif
|
|
||||||
// motor/esc/servo related stuff
|
// motor/esc/servo related stuff
|
||||||
|
motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS];
|
||||||
escAndServoConfig_t escAndServoConfig;
|
escAndServoConfig_t escAndServoConfig;
|
||||||
flight3DConfig_t flight3DConfig;
|
flight3DConfig_t flight3DConfig;
|
||||||
|
|
||||||
uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
|
uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
|
||||||
uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
|
uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
|
||||||
uint8_t use_fast_pwm; // Use fast PWM implementation when oneshot enabled
|
uint8_t use_fast_pwm; // Use fast PWM implementation when oneshot enabled
|
||||||
|
|
||||||
|
#ifdef USE_SERVOS
|
||||||
|
servoMixer_t customServoMixer[MAX_SERVO_RULES];
|
||||||
|
// Servo-related stuff
|
||||||
|
servoParam_t servoConf[MAX_SUPPORTED_SERVOS]; // servo configuration
|
||||||
|
// gimbal-related configuration
|
||||||
|
gimbalConfig_t gimbalConfig;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef CC3D
|
#ifdef CC3D
|
||||||
uint8_t use_buzzer_p6;
|
uint8_t use_buzzer_p6;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// global sensor-related stuff
|
// global sensor-related stuff
|
||||||
|
|
||||||
sensorAlignmentConfig_t sensorAlignmentConfig;
|
sensorAlignmentConfig_t sensorAlignmentConfig;
|
||||||
boardAlignment_t boardAlignment;
|
boardAlignment_t boardAlignment;
|
||||||
|
|
||||||
|
@ -59,17 +66,35 @@ typedef struct master_t {
|
||||||
|
|
||||||
uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
|
uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
|
||||||
uint8_t baro_hardware; // Barometer hardware to use
|
uint8_t baro_hardware; // Barometer hardware to use
|
||||||
|
int16_t mag_declination; // Get your magnetic decliniation from here : http://magnetic-declination.com/
|
||||||
|
// For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero.
|
||||||
|
|
||||||
|
rollAndPitchTrims_t accelerometerTrims; // accelerometer trim
|
||||||
|
|
||||||
|
uint8_t acc_lpf_hz; // Set the Low Pass Filter factor for ACC. Reducing this value would reduce ACC noise (visible in GUI), but would increase ACC lag time. Zero = no filter
|
||||||
|
float accz_lpf_cutoff; // cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz
|
||||||
|
accDeadband_t accDeadband;
|
||||||
|
barometerConfig_t barometerConfig;
|
||||||
|
uint8_t acc_unarmedcal; // turn automatic acc compensation on/off
|
||||||
|
|
||||||
|
uint16_t throttle_correction_angle; // the angle when the throttle correction is maximal. in 0.1 degres, ex 225 = 22.5 ,30.0, 450 = 45.0 deg
|
||||||
|
uint8_t throttle_correction_value; // the correction that will be applied at throttle_correction_angle.
|
||||||
|
batteryConfig_t batteryConfig;
|
||||||
|
|
||||||
|
// Radio/ESC-related configuration
|
||||||
|
rcControlsConfig_t rcControlsConfig;
|
||||||
|
|
||||||
|
#ifdef GPS
|
||||||
|
gpsProfile_t gpsProfile;
|
||||||
|
#endif
|
||||||
|
|
||||||
uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
|
uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
|
||||||
flightDynamicsTrims_t accZero;
|
flightDynamicsTrims_t accZero;
|
||||||
flightDynamicsTrims_t magZero;
|
flightDynamicsTrims_t magZero;
|
||||||
|
|
||||||
batteryConfig_t batteryConfig;
|
|
||||||
|
|
||||||
rxConfig_t rxConfig;
|
rxConfig_t rxConfig;
|
||||||
inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.
|
inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.
|
||||||
|
|
||||||
failsafeConfig_t failsafeConfig;
|
|
||||||
|
|
||||||
uint8_t retarded_arm; // allow disarm/arm on throttle down + roll left/right
|
uint8_t retarded_arm; // allow disarm/arm on throttle down + roll left/right
|
||||||
uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
|
uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
|
||||||
|
@ -78,15 +103,14 @@ typedef struct master_t {
|
||||||
|
|
||||||
// mixer-related configuration
|
// mixer-related configuration
|
||||||
mixerConfig_t mixerConfig;
|
mixerConfig_t mixerConfig;
|
||||||
|
|
||||||
airplaneConfig_t airplaneConfig;
|
airplaneConfig_t airplaneConfig;
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
gpsConfig_t gpsConfig;
|
gpsConfig_t gpsConfig;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
failsafeConfig_t failsafeConfig;
|
||||||
serialConfig_t serialConfig;
|
serialConfig_t serialConfig;
|
||||||
|
|
||||||
telemetryConfig_t telemetryConfig;
|
telemetryConfig_t telemetryConfig;
|
||||||
|
|
||||||
#ifdef LED_STRIP
|
#ifdef LED_STRIP
|
||||||
|
@ -100,7 +124,9 @@ typedef struct master_t {
|
||||||
|
|
||||||
profile_t profile[MAX_PROFILE_COUNT];
|
profile_t profile[MAX_PROFILE_COUNT];
|
||||||
uint8_t current_profile_index;
|
uint8_t current_profile_index;
|
||||||
controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT];
|
|
||||||
|
modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
|
||||||
|
adjustmentRange_t adjustmentRanges[MAX_ADJUSTMENT_RANGE_COUNT];
|
||||||
|
|
||||||
#ifdef BLACKBOX
|
#ifdef BLACKBOX
|
||||||
uint8_t blackbox_rate_num;
|
uint8_t blackbox_rate_num;
|
||||||
|
@ -108,8 +134,6 @@ typedef struct master_t {
|
||||||
uint8_t blackbox_device;
|
uint8_t blackbox_device;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
beeperOffConditions_t beeper_off;
|
|
||||||
|
|
||||||
uint8_t magic_ef; // magic number, should be 0xEF
|
uint8_t magic_ef; // magic number, should be 0xEF
|
||||||
uint8_t chk; // XOR checksum
|
uint8_t chk; // XOR checksum
|
||||||
} master_t;
|
} master_t;
|
||||||
|
|
|
@ -19,42 +19,5 @@
|
||||||
|
|
||||||
typedef struct profile_s {
|
typedef struct profile_s {
|
||||||
pidProfile_t pidProfile;
|
pidProfile_t pidProfile;
|
||||||
|
controlRateConfig_t controlRateProfile;
|
||||||
uint8_t defaultRateProfileIndex;
|
|
||||||
|
|
||||||
int16_t mag_declination; // Get your magnetic decliniation from here : http://magnetic-declination.com/
|
|
||||||
// For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero.
|
|
||||||
|
|
||||||
rollAndPitchTrims_t accelerometerTrims; // accelerometer trim
|
|
||||||
|
|
||||||
// sensor-related stuff
|
|
||||||
uint8_t acc_lpf_hz; // Set the Low Pass Filter factor for ACC. Reducing this value would reduce ACC noise (visible in GUI), but would increase ACC lag time. Zero = no filter
|
|
||||||
float accz_lpf_cutoff; // cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz
|
|
||||||
accDeadband_t accDeadband;
|
|
||||||
|
|
||||||
barometerConfig_t barometerConfig;
|
|
||||||
|
|
||||||
uint8_t acc_unarmedcal; // turn automatic acc compensation on/off
|
|
||||||
|
|
||||||
modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
|
|
||||||
|
|
||||||
adjustmentRange_t adjustmentRanges[MAX_ADJUSTMENT_RANGE_COUNT];
|
|
||||||
|
|
||||||
// Radio/ESC-related configuration
|
|
||||||
|
|
||||||
rcControlsConfig_t rcControlsConfig;
|
|
||||||
|
|
||||||
uint16_t throttle_correction_angle; // the angle when the throttle correction is maximal. in 0.1 degres, ex 225 = 22.5 ,30.0, 450 = 45.0 deg
|
|
||||||
uint8_t throttle_correction_value; // the correction that will be applied at throttle_correction_angle.
|
|
||||||
|
|
||||||
#ifdef USE_SERVOS
|
|
||||||
// Servo-related stuff
|
|
||||||
servoParam_t servoConf[MAX_SUPPORTED_SERVOS]; // servo configuration
|
|
||||||
// gimbal-related configuration
|
|
||||||
gimbalConfig_t gimbalConfig;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef GPS
|
|
||||||
gpsProfile_t gpsProfile;
|
|
||||||
#endif
|
|
||||||
} profile_t;
|
} profile_t;
|
||||||
|
|
|
@ -616,14 +616,14 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
||||||
break;
|
break;
|
||||||
case BST_SERVO_CONFIGURATIONS:
|
case BST_SERVO_CONFIGURATIONS:
|
||||||
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||||
bstWrite16(currentProfile->servoConf[i].min);
|
bstWrite16(masterConfig.servoConf[i].min);
|
||||||
bstWrite16(currentProfile->servoConf[i].max);
|
bstWrite16(masterConfig.servoConf[i].max);
|
||||||
bstWrite16(currentProfile->servoConf[i].middle);
|
bstWrite16(masterConfig.servoConf[i].middle);
|
||||||
bstWrite8(currentProfile->servoConf[i].rate);
|
bstWrite8(masterConfig.servoConf[i].rate);
|
||||||
bstWrite8(currentProfile->servoConf[i].angleAtMin);
|
bstWrite8(masterConfig.servoConf[i].angleAtMin);
|
||||||
bstWrite8(currentProfile->servoConf[i].angleAtMax);
|
bstWrite8(masterConfig.servoConf[i].angleAtMax);
|
||||||
bstWrite8(currentProfile->servoConf[i].forwardFromChannel);
|
bstWrite8(masterConfig.servoConf[i].forwardFromChannel);
|
||||||
bstWrite32(currentProfile->servoConf[i].reversedSources);
|
bstWrite32(masterConfig.servoConf[i].reversedSources);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case BST_SERVO_MIX_RULES:
|
case BST_SERVO_MIX_RULES:
|
||||||
|
@ -728,7 +728,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
||||||
break;
|
break;
|
||||||
case BST_MODE_RANGES:
|
case BST_MODE_RANGES:
|
||||||
for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
||||||
modeActivationCondition_t *mac = ¤tProfile->modeActivationConditions[i];
|
modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
|
||||||
const box_t *box = &boxes[mac->modeId];
|
const box_t *box = &boxes[mac->modeId];
|
||||||
bstWrite8(box->permanentId);
|
bstWrite8(box->permanentId);
|
||||||
bstWrite8(mac->auxChannelIndex);
|
bstWrite8(mac->auxChannelIndex);
|
||||||
|
@ -738,7 +738,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
||||||
break;
|
break;
|
||||||
case BST_ADJUSTMENT_RANGES:
|
case BST_ADJUSTMENT_RANGES:
|
||||||
for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
|
for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
|
||||||
adjustmentRange_t *adjRange = ¤tProfile->adjustmentRanges[i];
|
adjustmentRange_t *adjRange = &masterConfig.adjustmentRanges[i];
|
||||||
bstWrite8(adjRange->adjustmentIndex);
|
bstWrite8(adjRange->adjustmentIndex);
|
||||||
bstWrite8(adjRange->auxChannelIndex);
|
bstWrite8(adjRange->auxChannelIndex);
|
||||||
bstWrite8(adjRange->range.startStep);
|
bstWrite8(adjRange->range.startStep);
|
||||||
|
@ -781,7 +781,7 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
||||||
bstWrite8(masterConfig.rxConfig.rssi_channel);
|
bstWrite8(masterConfig.rxConfig.rssi_channel);
|
||||||
bstWrite8(0);
|
bstWrite8(0);
|
||||||
|
|
||||||
bstWrite16(currentProfile->mag_declination / 10);
|
bstWrite16(masterConfig.mag_declination / 10);
|
||||||
|
|
||||||
bstWrite8(masterConfig.batteryConfig.vbatscale);
|
bstWrite8(masterConfig.batteryConfig.vbatscale);
|
||||||
bstWrite8(masterConfig.batteryConfig.vbatmincellvoltage);
|
bstWrite8(masterConfig.batteryConfig.vbatmincellvoltage);
|
||||||
|
@ -845,8 +845,8 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
||||||
|
|
||||||
// Additional commands that are not compatible with MultiWii
|
// Additional commands that are not compatible with MultiWii
|
||||||
case BST_ACC_TRIM:
|
case BST_ACC_TRIM:
|
||||||
bstWrite16(currentProfile->accelerometerTrims.values.pitch);
|
bstWrite16(masterConfig.accelerometerTrims.values.pitch);
|
||||||
bstWrite16(currentProfile->accelerometerTrims.values.roll);
|
bstWrite16(masterConfig.accelerometerTrims.values.roll);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case BST_UID:
|
case BST_UID:
|
||||||
|
@ -987,10 +987,10 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
|
||||||
bstWrite32(0); // future exp
|
bstWrite32(0); // future exp
|
||||||
break;
|
break;
|
||||||
case BST_DEADBAND:
|
case BST_DEADBAND:
|
||||||
bstWrite8(currentProfile->rcControlsConfig.alt_hold_deadband);
|
bstWrite8(masterConfig.rcControlsConfig.alt_hold_deadband);
|
||||||
bstWrite8(currentProfile->rcControlsConfig.alt_hold_fast_change);
|
bstWrite8(masterConfig.rcControlsConfig.alt_hold_fast_change);
|
||||||
bstWrite8(currentProfile->rcControlsConfig.deadband);
|
bstWrite8(masterConfig.rcControlsConfig.deadband);
|
||||||
bstWrite8(currentProfile->rcControlsConfig.yaw_deadband);
|
bstWrite8(masterConfig.rcControlsConfig.yaw_deadband);
|
||||||
break;
|
break;
|
||||||
case BST_FC_FILTERS:
|
case BST_FC_FILTERS:
|
||||||
bstWrite16(constrain(masterConfig.gyro_lpf, 0, 1)); // Extra safety to prevent OSD setting corrupt values
|
bstWrite16(constrain(masterConfig.gyro_lpf, 0, 1)); // Extra safety to prevent OSD setting corrupt values
|
||||||
|
@ -1045,8 +1045,8 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
case BST_SET_ACC_TRIM:
|
case BST_SET_ACC_TRIM:
|
||||||
currentProfile->accelerometerTrims.values.pitch = bstRead16();
|
masterConfig.accelerometerTrims.values.pitch = bstRead16();
|
||||||
currentProfile->accelerometerTrims.values.roll = bstRead16();
|
masterConfig.accelerometerTrims.values.roll = bstRead16();
|
||||||
break;
|
break;
|
||||||
case BST_SET_ARMING_CONFIG:
|
case BST_SET_ARMING_CONFIG:
|
||||||
masterConfig.auto_disarm_delay = bstRead8();
|
masterConfig.auto_disarm_delay = bstRead8();
|
||||||
|
@ -1089,7 +1089,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
||||||
case BST_SET_MODE_RANGE:
|
case BST_SET_MODE_RANGE:
|
||||||
i = bstRead8();
|
i = bstRead8();
|
||||||
if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
|
if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
|
||||||
modeActivationCondition_t *mac = ¤tProfile->modeActivationConditions[i];
|
modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
|
||||||
i = bstRead8();
|
i = bstRead8();
|
||||||
const box_t *box = findBoxByPermenantId(i);
|
const box_t *box = findBoxByPermenantId(i);
|
||||||
if (box) {
|
if (box) {
|
||||||
|
@ -1098,7 +1098,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
||||||
mac->range.startStep = bstRead8();
|
mac->range.startStep = bstRead8();
|
||||||
mac->range.endStep = bstRead8();
|
mac->range.endStep = bstRead8();
|
||||||
|
|
||||||
useRcControlsConfig(currentProfile->modeActivationConditions, &masterConfig.escAndServoConfig, ¤tProfile->pidProfile);
|
useRcControlsConfig(masterConfig.modeActivationConditions, &masterConfig.escAndServoConfig, ¤tProfile->pidProfile);
|
||||||
} else {
|
} else {
|
||||||
ret = BST_FAILED;
|
ret = BST_FAILED;
|
||||||
}
|
}
|
||||||
|
@ -1109,7 +1109,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
||||||
case BST_SET_ADJUSTMENT_RANGE:
|
case BST_SET_ADJUSTMENT_RANGE:
|
||||||
i = bstRead8();
|
i = bstRead8();
|
||||||
if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
|
if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
|
||||||
adjustmentRange_t *adjRange = ¤tProfile->adjustmentRanges[i];
|
adjustmentRange_t *adjRange = &masterConfig.adjustmentRanges[i];
|
||||||
i = bstRead8();
|
i = bstRead8();
|
||||||
if (i < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
|
if (i < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
|
||||||
adjRange->adjustmentIndex = i;
|
adjRange->adjustmentIndex = i;
|
||||||
|
@ -1169,7 +1169,7 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
||||||
masterConfig.rxConfig.rssi_channel = bstRead8();
|
masterConfig.rxConfig.rssi_channel = bstRead8();
|
||||||
bstRead8();
|
bstRead8();
|
||||||
|
|
||||||
currentProfile->mag_declination = bstRead16() * 10;
|
masterConfig.mag_declination = bstRead16() * 10;
|
||||||
|
|
||||||
masterConfig.batteryConfig.vbatscale = bstRead8(); // actual vbatscale as intended
|
masterConfig.batteryConfig.vbatscale = bstRead8(); // actual vbatscale as intended
|
||||||
masterConfig.batteryConfig.vbatmincellvoltage = bstRead8(); // vbatlevel_warn1 in MWC2.3 GUI
|
masterConfig.batteryConfig.vbatmincellvoltage = bstRead8(); // vbatlevel_warn1 in MWC2.3 GUI
|
||||||
|
@ -1190,14 +1190,14 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
||||||
if (i >= MAX_SUPPORTED_SERVOS) {
|
if (i >= MAX_SUPPORTED_SERVOS) {
|
||||||
ret = BST_FAILED;
|
ret = BST_FAILED;
|
||||||
} else {
|
} else {
|
||||||
currentProfile->servoConf[i].min = bstRead16();
|
masterConfig.servoConf[i].min = bstRead16();
|
||||||
currentProfile->servoConf[i].max = bstRead16();
|
masterConfig.servoConf[i].max = bstRead16();
|
||||||
currentProfile->servoConf[i].middle = bstRead16();
|
masterConfig.servoConf[i].middle = bstRead16();
|
||||||
currentProfile->servoConf[i].rate = bstRead8();
|
masterConfig.servoConf[i].rate = bstRead8();
|
||||||
currentProfile->servoConf[i].angleAtMin = bstRead8();
|
masterConfig.servoConf[i].angleAtMin = bstRead8();
|
||||||
currentProfile->servoConf[i].angleAtMax = bstRead8();
|
masterConfig.servoConf[i].angleAtMax = bstRead8();
|
||||||
currentProfile->servoConf[i].forwardFromChannel = bstRead8();
|
masterConfig.servoConf[i].forwardFromChannel = bstRead8();
|
||||||
currentProfile->servoConf[i].reversedSources = bstRead32();
|
masterConfig.servoConf[i].reversedSources = bstRead32();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
@ -1451,10 +1451,10 @@ static bool bstSlaveProcessWriteCommand(uint8_t bstWriteCommand)
|
||||||
DISABLE_ARMING_FLAG(PREVENT_ARMING);
|
DISABLE_ARMING_FLAG(PREVENT_ARMING);
|
||||||
break;
|
break;
|
||||||
case BST_SET_DEADBAND:
|
case BST_SET_DEADBAND:
|
||||||
currentProfile->rcControlsConfig.alt_hold_deadband = bstRead8();
|
masterConfig.rcControlsConfig.alt_hold_deadband = bstRead8();
|
||||||
currentProfile->rcControlsConfig.alt_hold_fast_change = bstRead8();
|
masterConfig.rcControlsConfig.alt_hold_fast_change = bstRead8();
|
||||||
currentProfile->rcControlsConfig.deadband = bstRead8();
|
masterConfig.rcControlsConfig.deadband = bstRead8();
|
||||||
currentProfile->rcControlsConfig.yaw_deadband = bstRead8();
|
masterConfig.rcControlsConfig.yaw_deadband = bstRead8();
|
||||||
break;
|
break;
|
||||||
case BST_SET_FC_FILTERS:
|
case BST_SET_FC_FILTERS:
|
||||||
masterConfig.gyro_lpf = bstRead16();
|
masterConfig.gyro_lpf = bstRead16();
|
||||||
|
|
|
@ -651,8 +651,7 @@ void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustm
|
||||||
};
|
};
|
||||||
}
|
}
|
||||||
|
|
||||||
void changeControlRateProfile(uint8_t profileIndex);
|
/* Is this needed ?
|
||||||
|
|
||||||
void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
|
void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
|
||||||
{
|
{
|
||||||
bool applied = false;
|
bool applied = false;
|
||||||
|
@ -660,7 +659,7 @@ void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
|
||||||
switch(adjustmentFunction) {
|
switch(adjustmentFunction) {
|
||||||
case ADJUSTMENT_RATE_PROFILE:
|
case ADJUSTMENT_RATE_PROFILE:
|
||||||
if (getCurrentControlRateProfile() != position) {
|
if (getCurrentControlRateProfile() != position) {
|
||||||
changeControlRateProfile(position);
|
changeProfile(position); // Is this safe to change profile "in flight" ?
|
||||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RATE_PROFILE, position);
|
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RATE_PROFILE, position);
|
||||||
applied = true;
|
applied = true;
|
||||||
}
|
}
|
||||||
|
@ -671,7 +670,7 @@ void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position)
|
||||||
beeperConfirmationBeeps(position + 1);
|
beeperConfirmationBeeps(position + 1);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
*/
|
||||||
#define RESET_FREQUENCY_2HZ (1000 / 2)
|
#define RESET_FREQUENCY_2HZ (1000 / 2)
|
||||||
|
|
||||||
void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rxConfig)
|
void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rxConfig)
|
||||||
|
@ -728,7 +727,7 @@ void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rx
|
||||||
uint16_t rangeWidth = ((2100 - 900) / adjustmentState->config->data.selectConfig.switchPositions);
|
uint16_t rangeWidth = ((2100 - 900) / adjustmentState->config->data.selectConfig.switchPositions);
|
||||||
uint8_t position = (constrain(rcData[channelIndex], 900, 2100 - 1) - 900) / rangeWidth;
|
uint8_t position = (constrain(rcData[channelIndex], 900, 2100 - 1) - 900) / rangeWidth;
|
||||||
|
|
||||||
applySelectAdjustment(adjustmentFunction, position);
|
// applySelectAdjustment(adjustmentFunction, position);
|
||||||
}
|
}
|
||||||
MARK_ADJUSTMENT_FUNCTION_AS_BUSY(adjustmentIndex);
|
MARK_ADJUSTMENT_FUNCTION_AS_BUSY(adjustmentIndex);
|
||||||
}
|
}
|
||||||
|
|
|
@ -185,10 +185,10 @@ typedef enum {
|
||||||
ADJUSTMENT_ROLL_P,
|
ADJUSTMENT_ROLL_P,
|
||||||
ADJUSTMENT_ROLL_I,
|
ADJUSTMENT_ROLL_I,
|
||||||
ADJUSTMENT_ROLL_D,
|
ADJUSTMENT_ROLL_D,
|
||||||
|
ADJUSTMENT_FUNCTION_COUNT,
|
||||||
|
|
||||||
} adjustmentFunction_e;
|
} adjustmentFunction_e;
|
||||||
|
|
||||||
#define ADJUSTMENT_FUNCTION_COUNT 21
|
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
ADJUSTMENT_MODE_STEP,
|
ADJUSTMENT_MODE_STEP,
|
||||||
|
@ -240,7 +240,7 @@ typedef struct adjustmentState_s {
|
||||||
#define MAX_SIMULTANEOUS_ADJUSTMENT_COUNT 4 // enough for 4 x 3position switches / 4 aux channel
|
#define MAX_SIMULTANEOUS_ADJUSTMENT_COUNT 4 // enough for 4 x 3position switches / 4 aux channel
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define MAX_ADJUSTMENT_RANGE_COUNT 12 // enough for 2 * 6pos switches.
|
#define MAX_ADJUSTMENT_RANGE_COUNT 15
|
||||||
|
|
||||||
void resetAdjustmentStates(void);
|
void resetAdjustmentStates(void);
|
||||||
void configureAdjustment(uint8_t index, uint8_t auxChannelIndex, const adjustmentConfig_t *adjustmentConfig);
|
void configureAdjustment(uint8_t index, uint8_t auxChannelIndex, const adjustmentConfig_t *adjustmentConfig);
|
||||||
|
|
|
@ -113,7 +113,6 @@ static void cliFeature(char *cmdline);
|
||||||
static void cliMotor(char *cmdline);
|
static void cliMotor(char *cmdline);
|
||||||
static void cliPlaySound(char *cmdline);
|
static void cliPlaySound(char *cmdline);
|
||||||
static void cliProfile(char *cmdline);
|
static void cliProfile(char *cmdline);
|
||||||
static void cliRateProfile(char *cmdline);
|
|
||||||
static void cliReboot(void);
|
static void cliReboot(void);
|
||||||
static void cliSave(char *cmdline);
|
static void cliSave(char *cmdline);
|
||||||
static void cliSerial(char *cmdline);
|
static void cliSerial(char *cmdline);
|
||||||
|
@ -280,8 +279,6 @@ const clicmd_t cmdTable[] = {
|
||||||
"[<index>]\r\n", cliPlaySound),
|
"[<index>]\r\n", cliPlaySound),
|
||||||
CLI_COMMAND_DEF("profile", "change profile",
|
CLI_COMMAND_DEF("profile", "change profile",
|
||||||
"[<index>]", cliProfile),
|
"[<index>]", cliProfile),
|
||||||
CLI_COMMAND_DEF("rateprofile", "change rate profile",
|
|
||||||
"[<index>]", cliRateProfile),
|
|
||||||
CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
|
CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
|
||||||
CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
|
CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
|
||||||
CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
|
CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
|
||||||
|
@ -464,7 +461,6 @@ typedef enum {
|
||||||
// value section
|
// value section
|
||||||
MASTER_VALUE = (0 << VALUE_SECTION_OFFSET),
|
MASTER_VALUE = (0 << VALUE_SECTION_OFFSET),
|
||||||
PROFILE_VALUE = (1 << VALUE_SECTION_OFFSET),
|
PROFILE_VALUE = (1 << VALUE_SECTION_OFFSET),
|
||||||
CONTROL_RATE_VALUE = (2 << VALUE_SECTION_OFFSET),
|
|
||||||
|
|
||||||
// value mode
|
// value mode
|
||||||
MODE_DIRECT = (0 << VALUE_MODE_OFFSET),
|
MODE_DIRECT = (0 << VALUE_MODE_OFFSET),
|
||||||
|
@ -550,11 +546,11 @@ const clivalue_t valueTable[] = {
|
||||||
{ "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDNAVR], .config.minmax = { 0, 200 } },
|
{ "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDNAVR], .config.minmax = { 0, 200 } },
|
||||||
{ "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDNAVR], .config.minmax = { 0, 200 } },
|
{ "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDNAVR], .config.minmax = { 0, 200 } },
|
||||||
{ "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDNAVR], .config.minmax = { 0, 200 } },
|
{ "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDNAVR], .config.minmax = { 0, 200 } },
|
||||||
{ "gps_wp_radius", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].gpsProfile.gps_wp_radius, .config.minmax = { 0, 2000 } },
|
{ "gps_wp_radius", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.gps_wp_radius, .config.minmax = { 0, 2000 } },
|
||||||
{ "nav_controls_heading", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].gpsProfile.nav_controls_heading, .config.lookup = { TABLE_OFF_ON } },
|
{ "nav_controls_heading", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsProfile.nav_controls_heading, .config.lookup = { TABLE_OFF_ON } },
|
||||||
{ "nav_speed_min", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].gpsProfile.nav_speed_min, .config.minmax = { 10, 2000 } },
|
{ "nav_speed_min", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_min, .config.minmax = { 10, 2000 } },
|
||||||
{ "nav_speed_max", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].gpsProfile.nav_speed_max, .config.minmax = { 10, 2000 } },
|
{ "nav_speed_max", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_max, .config.minmax = { 10, 2000 } },
|
||||||
{ "nav_slew_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].gpsProfile.nav_slew_rate, .config.minmax = { 0, 100 } },
|
{ "nav_slew_rate", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsProfile.nav_slew_rate, .config.minmax = { 0, 100 } },
|
||||||
#endif
|
#endif
|
||||||
#ifdef GTUNE
|
#ifdef GTUNE
|
||||||
{ "gtune_loP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_ROLL], .config.minmax = { 10, 200 } },
|
{ "gtune_loP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_ROLL], .config.minmax = { 10, 200 } },
|
||||||
|
@ -606,13 +602,13 @@ const clivalue_t valueTable[] = {
|
||||||
{ "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } },
|
{ "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } },
|
||||||
{ "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } },
|
{ "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } },
|
||||||
|
|
||||||
{ "alt_hold_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.alt_hold_deadband, .config.minmax = { 1, 250 } },
|
{ "alt_hold_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.alt_hold_deadband, .config.minmax = { 1, 250 } },
|
||||||
{ "alt_hold_fast_change", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].rcControlsConfig.alt_hold_fast_change, .config.lookup = { TABLE_OFF_ON } },
|
{ "alt_hold_fast_change", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rcControlsConfig.alt_hold_fast_change, .config.lookup = { TABLE_OFF_ON } },
|
||||||
{ "deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.deadband, .config.minmax = { 0, 32 } },
|
{ "deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.deadband, .config.minmax = { 0, 32 } },
|
||||||
{ "yaw_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.yaw_deadband, .config.minmax = { 0, 100 } },
|
{ "yaw_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.yaw_deadband, .config.minmax = { 0, 100 } },
|
||||||
|
|
||||||
{ "throttle_correction_value", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].throttle_correction_value, .config.minmax = { 0, 150 } },
|
{ "throttle_correction_value", VAR_UINT8 | MASTER_VALUE, &masterConfig.throttle_correction_value, .config.minmax = { 0, 150 } },
|
||||||
{ "throttle_correction_angle", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].throttle_correction_angle, .config.minmax = { 1, 900 } },
|
{ "throttle_correction_angle", VAR_UINT16 | MASTER_VALUE, &masterConfig.throttle_correction_angle, .config.minmax = { 1, 900 } },
|
||||||
|
|
||||||
{ "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, .config.minmax = { -1, 1 } },
|
{ "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, .config.minmax = { -1, 1 } },
|
||||||
|
|
||||||
|
@ -625,17 +621,16 @@ const clivalue_t valueTable[] = {
|
||||||
{ "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON } },
|
{ "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON } },
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
{ "default_rate_profile", VAR_UINT8 | PROFILE_VALUE , &masterConfig.profile[0].defaultRateProfileIndex, .config.minmax = { 0, MAX_CONTROL_RATE_PROFILE_COUNT - 1 } },
|
{ "rc_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rcRate8, .config.minmax = { 0, 250 } },
|
||||||
{ "rc_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcRate8, .config.minmax = { 0, 250 } },
|
{ "rc_expo", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rcExpo8, .config.minmax = { 0, 100 } },
|
||||||
{ "rc_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcExpo8, .config.minmax = { 0, 100 } },
|
{ "rc_yaw_expo", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rcYawExpo8, .config.minmax = { 0, 100 } },
|
||||||
{ "rc_yaw_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcYawExpo8, .config.minmax = { 0, 100 } },
|
{ "thr_mid", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.thrMid8, .config.minmax = { 0, 100 } },
|
||||||
{ "thr_mid", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrMid8, .config.minmax = { 0, 100 } },
|
{ "thr_expo", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.thrExpo8, .config.minmax = { 0, 100 } },
|
||||||
{ "thr_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrExpo8, .config.minmax = { 0, 100 } },
|
{ "roll_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rates[FD_ROLL], .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX } },
|
||||||
{ "roll_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_ROLL], .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX } },
|
{ "pitch_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rates[FD_PITCH], .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX } },
|
||||||
{ "pitch_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_PITCH], .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX } },
|
{ "yaw_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rates[FD_YAW], .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX } },
|
||||||
{ "yaw_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_YAW], .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX } },
|
{ "tpa_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX} },
|
||||||
{ "tpa_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX} },
|
{ "tpa_breakpoint", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX} },
|
||||||
{ "tpa_breakpoint", VAR_UINT16 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX} },
|
|
||||||
|
|
||||||
{ "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, .config.minmax = { 0, 200 } },
|
{ "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, .config.minmax = { 0, 200 } },
|
||||||
{ "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, .config.minmax = { 0, 200 } },
|
{ "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, .config.minmax = { 0, 200 } },
|
||||||
|
@ -647,26 +642,26 @@ const clivalue_t valueTable[] = {
|
||||||
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_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 } },
|
||||||
|
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
{ "gimbal_mode", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].gimbalConfig.mode, .config.lookup = { TABLE_GIMBAL_MODE } },
|
{ "gimbal_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gimbalConfig.mode, .config.lookup = { TABLE_GIMBAL_MODE } },
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
{ "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
|
{ "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
|
||||||
{ "acc_lpf_hz", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].acc_lpf_hz, .config.minmax = { 0, 200 } },
|
{ "acc_lpf_hz", VAR_UINT8 | MASTER_VALUE, &masterConfig.acc_lpf_hz, .config.minmax = { 0, 200 } },
|
||||||
{ "accxy_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].accDeadband.xy, .config.minmax = { 0, 100 } },
|
{ "accxy_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.xy, .config.minmax = { 0, 100 } },
|
||||||
{ "accz_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].accDeadband.z, .config.minmax = { 0, 100 } },
|
{ "accz_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.z, .config.minmax = { 0, 100 } },
|
||||||
{ "accz_lpf_cutoff", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].accz_lpf_cutoff, .config.minmax = { 1, 20 } },
|
{ "accz_lpf_cutoff", VAR_FLOAT | MASTER_VALUE, &masterConfig.accz_lpf_cutoff, .config.minmax = { 1, 20 } },
|
||||||
{ "acc_unarmedcal", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].acc_unarmedcal, .config.lookup = { TABLE_OFF_ON } },
|
{ "acc_unarmedcal", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_unarmedcal, .config.lookup = { TABLE_OFF_ON } },
|
||||||
{ "acc_trim_pitch", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].accelerometerTrims.values.pitch, .config.minmax = { -300, 300 } },
|
{ "acc_trim_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.pitch, .config.minmax = { -300, 300 } },
|
||||||
{ "acc_trim_roll", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].accelerometerTrims.values.roll, .config.minmax = { -300, 300 } },
|
{ "acc_trim_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.roll, .config.minmax = { -300, 300 } },
|
||||||
|
|
||||||
{ "baro_tab_size", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].barometerConfig.baro_sample_count, .config.minmax = { 0, BARO_SAMPLE_COUNT_MAX } },
|
{ "baro_tab_size", VAR_UINT8 | MASTER_VALUE, &masterConfig.barometerConfig.baro_sample_count, .config.minmax = { 0, BARO_SAMPLE_COUNT_MAX } },
|
||||||
{ "baro_noise_lpf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].barometerConfig.baro_noise_lpf, .config.minmax = { 0 , 1 } },
|
{ "baro_noise_lpf", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_noise_lpf, .config.minmax = { 0 , 1 } },
|
||||||
{ "baro_cf_vel", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].barometerConfig.baro_cf_vel, .config.minmax = { 0 , 1 } },
|
{ "baro_cf_vel", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_vel, .config.minmax = { 0 , 1 } },
|
||||||
{ "baro_cf_alt", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].barometerConfig.baro_cf_alt, .config.minmax = { 0 , 1 } },
|
{ "baro_cf_alt", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_alt, .config.minmax = { 0 , 1 } },
|
||||||
{ "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
|
{ "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
|
||||||
|
|
||||||
{ "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
|
{ "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
|
||||||
{ "mag_declination", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].mag_declination, .config.minmax = { -18000, 18000 } },
|
{ "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.mag_declination, .config.minmax = { -18000, 18000 } },
|
||||||
{ "delta_from_gyro", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.deltaFromGyro, .config.lookup = { TABLE_OFF_ON } },
|
{ "delta_from_gyro", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.deltaFromGyro, .config.lookup = { TABLE_OFF_ON } },
|
||||||
|
|
||||||
{ "pid_controller", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidController, .config.lookup = { TABLE_PID_CONTROLLER } },
|
{ "pid_controller", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidController, .config.lookup = { TABLE_PID_CONTROLLER } },
|
||||||
|
@ -875,7 +870,7 @@ static void cliAux(char *cmdline)
|
||||||
if (isEmpty(cmdline)) {
|
if (isEmpty(cmdline)) {
|
||||||
// print out aux channel settings
|
// print out aux channel settings
|
||||||
for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
||||||
modeActivationCondition_t *mac = ¤tProfile->modeActivationConditions[i];
|
modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
|
||||||
cliPrintf("aux %u %u %u %u %u\r\n",
|
cliPrintf("aux %u %u %u %u %u\r\n",
|
||||||
i,
|
i,
|
||||||
mac->modeId,
|
mac->modeId,
|
||||||
|
@ -888,7 +883,7 @@ static void cliAux(char *cmdline)
|
||||||
ptr = cmdline;
|
ptr = cmdline;
|
||||||
i = atoi(ptr++);
|
i = atoi(ptr++);
|
||||||
if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
|
if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
|
||||||
modeActivationCondition_t *mac = ¤tProfile->modeActivationConditions[i];
|
modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
|
||||||
uint8_t validArgumentCount = 0;
|
uint8_t validArgumentCount = 0;
|
||||||
ptr = strchr(ptr, ' ');
|
ptr = strchr(ptr, ' ');
|
||||||
if (ptr) {
|
if (ptr) {
|
||||||
|
@ -1022,7 +1017,7 @@ static void cliAdjustmentRange(char *cmdline)
|
||||||
if (isEmpty(cmdline)) {
|
if (isEmpty(cmdline)) {
|
||||||
// print out adjustment ranges channel settings
|
// print out adjustment ranges channel settings
|
||||||
for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
|
for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
|
||||||
adjustmentRange_t *ar = ¤tProfile->adjustmentRanges[i];
|
adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
|
||||||
cliPrintf("adjrange %u %u %u %u %u %u %u\r\n",
|
cliPrintf("adjrange %u %u %u %u %u %u %u\r\n",
|
||||||
i,
|
i,
|
||||||
ar->adjustmentIndex,
|
ar->adjustmentIndex,
|
||||||
|
@ -1037,7 +1032,7 @@ static void cliAdjustmentRange(char *cmdline)
|
||||||
ptr = cmdline;
|
ptr = cmdline;
|
||||||
i = atoi(ptr++);
|
i = atoi(ptr++);
|
||||||
if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
|
if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
|
||||||
adjustmentRange_t *ar = ¤tProfile->adjustmentRanges[i];
|
adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
|
||||||
uint8_t validArgumentCount = 0;
|
uint8_t validArgumentCount = 0;
|
||||||
|
|
||||||
ptr = strchr(ptr, ' ');
|
ptr = strchr(ptr, ' ');
|
||||||
|
@ -1281,7 +1276,7 @@ static void cliServo(char *cmdline)
|
||||||
if (isEmpty(cmdline)) {
|
if (isEmpty(cmdline)) {
|
||||||
// print out servo settings
|
// print out servo settings
|
||||||
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||||
servo = ¤tProfile->servoConf[i];
|
servo = &masterConfig.servoConf[i];
|
||||||
|
|
||||||
cliPrintf("servo %u %d %d %d %d %d %d %d\r\n",
|
cliPrintf("servo %u %d %d %d %d %d %d %d\r\n",
|
||||||
i,
|
i,
|
||||||
|
@ -1332,7 +1327,7 @@ static void cliServo(char *cmdline)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
servo = ¤tProfile->servoConf[i];
|
servo = &masterConfig.servoConf[i];
|
||||||
|
|
||||||
if (
|
if (
|
||||||
arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX ||
|
arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX ||
|
||||||
|
@ -1393,7 +1388,7 @@ static void cliServoMix(char *cmdline)
|
||||||
// erase custom mixer
|
// erase custom mixer
|
||||||
memset(masterConfig.customServoMixer, 0, sizeof(masterConfig.customServoMixer));
|
memset(masterConfig.customServoMixer, 0, sizeof(masterConfig.customServoMixer));
|
||||||
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||||
currentProfile->servoConf[i].reversedSources = 0;
|
masterConfig.servoConf[i].reversedSources = 0;
|
||||||
}
|
}
|
||||||
} else if (strncasecmp(cmdline, "load", 4) == 0) {
|
} else if (strncasecmp(cmdline, "load", 4) == 0) {
|
||||||
ptr = strchr(cmdline, ' ');
|
ptr = strchr(cmdline, ' ');
|
||||||
|
@ -1427,7 +1422,7 @@ static void cliServoMix(char *cmdline)
|
||||||
for (servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
|
for (servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
|
||||||
cliPrintf("%d", servoIndex);
|
cliPrintf("%d", servoIndex);
|
||||||
for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
|
for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
|
||||||
cliPrintf("\t%s ", (currentProfile->servoConf[servoIndex].reversedSources & (1 << inputSource)) ? "r" : "n");
|
cliPrintf("\t%s ", (masterConfig.servoConf[servoIndex].reversedSources & (1 << inputSource)) ? "r" : "n");
|
||||||
cliPrintf("\r\n");
|
cliPrintf("\r\n");
|
||||||
}
|
}
|
||||||
return;
|
return;
|
||||||
|
@ -1448,9 +1443,9 @@ static void cliServoMix(char *cmdline)
|
||||||
&& args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT
|
&& args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT
|
||||||
&& (*ptr == 'r' || *ptr == 'n')) {
|
&& (*ptr == 'r' || *ptr == 'n')) {
|
||||||
if (*ptr == 'r')
|
if (*ptr == 'r')
|
||||||
currentProfile->servoConf[args[SERVO]].reversedSources |= 1 << args[INPUT];
|
masterConfig.servoConf[args[SERVO]].reversedSources |= 1 << args[INPUT];
|
||||||
else
|
else
|
||||||
currentProfile->servoConf[args[SERVO]].reversedSources &= ~(1 << args[INPUT]);
|
masterConfig.servoConf[args[SERVO]].reversedSources &= ~(1 << args[INPUT]);
|
||||||
} else
|
} else
|
||||||
cliShowParseError();
|
cliShowParseError();
|
||||||
|
|
||||||
|
@ -1669,10 +1664,9 @@ static void dumpValues(uint16_t valueSection)
|
||||||
typedef enum {
|
typedef enum {
|
||||||
DUMP_MASTER = (1 << 0),
|
DUMP_MASTER = (1 << 0),
|
||||||
DUMP_PROFILE = (1 << 1),
|
DUMP_PROFILE = (1 << 1),
|
||||||
DUMP_CONTROL_RATE_PROFILE = (1 << 2)
|
|
||||||
} dumpFlags_e;
|
} dumpFlags_e;
|
||||||
|
|
||||||
#define DUMP_ALL (DUMP_MASTER | DUMP_PROFILE | DUMP_CONTROL_RATE_PROFILE)
|
#define DUMP_ALL (DUMP_MASTER | DUMP_PROFILE)
|
||||||
|
|
||||||
|
|
||||||
static const char* const sectionBreak = "\r\n";
|
static const char* const sectionBreak = "\r\n";
|
||||||
|
@ -1696,9 +1690,6 @@ static void cliDump(char *cmdline)
|
||||||
if (strcasecmp(cmdline, "profile") == 0) {
|
if (strcasecmp(cmdline, "profile") == 0) {
|
||||||
dumpMask = DUMP_PROFILE; // only
|
dumpMask = DUMP_PROFILE; // only
|
||||||
}
|
}
|
||||||
if (strcasecmp(cmdline, "rates") == 0) {
|
|
||||||
dumpMask = DUMP_CONTROL_RATE_PROFILE; // only
|
|
||||||
}
|
|
||||||
|
|
||||||
if (dumpMask & DUMP_MASTER) {
|
if (dumpMask & DUMP_MASTER) {
|
||||||
|
|
||||||
|
@ -1837,17 +1828,6 @@ static void cliDump(char *cmdline)
|
||||||
|
|
||||||
dumpValues(PROFILE_VALUE);
|
dumpValues(PROFILE_VALUE);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (dumpMask & DUMP_CONTROL_RATE_PROFILE) {
|
|
||||||
cliPrint("\r\n# dump rates\r\n");
|
|
||||||
|
|
||||||
cliPrint("\r\n# rateprofile\r\n");
|
|
||||||
cliRateProfile("");
|
|
||||||
|
|
||||||
printSectionBreak();
|
|
||||||
|
|
||||||
dumpValues(CONTROL_RATE_VALUE);
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void cliEnter(serialPort_t *serialPort)
|
void cliEnter(serialPort_t *serialPort)
|
||||||
|
@ -2143,22 +2123,6 @@ static void cliProfile(char *cmdline)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void cliRateProfile(char *cmdline)
|
|
||||||
{
|
|
||||||
int i;
|
|
||||||
|
|
||||||
if (isEmpty(cmdline)) {
|
|
||||||
cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfile());
|
|
||||||
return;
|
|
||||||
} else {
|
|
||||||
i = atoi(cmdline);
|
|
||||||
if (i >= 0 && i < MAX_CONTROL_RATE_PROFILE_COUNT) {
|
|
||||||
changeControlRateProfile(i);
|
|
||||||
cliRateProfile("");
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static void cliReboot(void) {
|
static void cliReboot(void) {
|
||||||
cliPrint("\r\nRebooting");
|
cliPrint("\r\nRebooting");
|
||||||
bufWriterFlush(cliWriter);
|
bufWriterFlush(cliWriter);
|
||||||
|
@ -2220,9 +2184,6 @@ static void cliPrintVar(const clivalue_t *var, uint32_t full)
|
||||||
if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
|
if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
|
||||||
ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
|
ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
|
||||||
}
|
}
|
||||||
if ((var->type & VALUE_SECTION_MASK) == CONTROL_RATE_VALUE) {
|
|
||||||
ptr = ((uint8_t *)ptr) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
|
|
||||||
}
|
|
||||||
|
|
||||||
switch (var->type & VALUE_TYPE_MASK) {
|
switch (var->type & VALUE_TYPE_MASK) {
|
||||||
case VAR_UINT8:
|
case VAR_UINT8:
|
||||||
|
@ -2273,9 +2234,6 @@ static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
|
||||||
if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
|
if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
|
||||||
ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
|
ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
|
||||||
}
|
}
|
||||||
if ((var->type & VALUE_SECTION_MASK) == CONTROL_RATE_VALUE) {
|
|
||||||
ptr = ((uint8_t *)ptr) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
|
|
||||||
}
|
|
||||||
|
|
||||||
switch (var->type & VALUE_TYPE_MASK) {
|
switch (var->type & VALUE_TYPE_MASK) {
|
||||||
case VAR_UINT8:
|
case VAR_UINT8:
|
||||||
|
|
|
@ -713,14 +713,14 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
case MSP_SERVO_CONFIGURATIONS:
|
case MSP_SERVO_CONFIGURATIONS:
|
||||||
headSerialReply(MAX_SUPPORTED_SERVOS * sizeof(servoParam_t));
|
headSerialReply(MAX_SUPPORTED_SERVOS * sizeof(servoParam_t));
|
||||||
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
|
||||||
serialize16(currentProfile->servoConf[i].min);
|
serialize16(masterConfig.servoConf[i].min);
|
||||||
serialize16(currentProfile->servoConf[i].max);
|
serialize16(masterConfig.servoConf[i].max);
|
||||||
serialize16(currentProfile->servoConf[i].middle);
|
serialize16(masterConfig.servoConf[i].middle);
|
||||||
serialize8(currentProfile->servoConf[i].rate);
|
serialize8(masterConfig.servoConf[i].rate);
|
||||||
serialize8(currentProfile->servoConf[i].angleAtMin);
|
serialize8(masterConfig.servoConf[i].angleAtMin);
|
||||||
serialize8(currentProfile->servoConf[i].angleAtMax);
|
serialize8(masterConfig.servoConf[i].angleAtMax);
|
||||||
serialize8(currentProfile->servoConf[i].forwardFromChannel);
|
serialize8(masterConfig.servoConf[i].forwardFromChannel);
|
||||||
serialize32(currentProfile->servoConf[i].reversedSources);
|
serialize32(masterConfig.servoConf[i].reversedSources);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case MSP_SERVO_MIX_RULES:
|
case MSP_SERVO_MIX_RULES:
|
||||||
|
@ -837,7 +837,7 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
case MSP_MODE_RANGES:
|
case MSP_MODE_RANGES:
|
||||||
headSerialReply(4 * MAX_MODE_ACTIVATION_CONDITION_COUNT);
|
headSerialReply(4 * MAX_MODE_ACTIVATION_CONDITION_COUNT);
|
||||||
for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
|
||||||
modeActivationCondition_t *mac = ¤tProfile->modeActivationConditions[i];
|
modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
|
||||||
const box_t *box = &boxes[mac->modeId];
|
const box_t *box = &boxes[mac->modeId];
|
||||||
serialize8(box->permanentId);
|
serialize8(box->permanentId);
|
||||||
serialize8(mac->auxChannelIndex);
|
serialize8(mac->auxChannelIndex);
|
||||||
|
@ -855,7 +855,7 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
1 // aux switch channel index
|
1 // aux switch channel index
|
||||||
));
|
));
|
||||||
for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
|
for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
|
||||||
adjustmentRange_t *adjRange = ¤tProfile->adjustmentRanges[i];
|
adjustmentRange_t *adjRange = &masterConfig.adjustmentRanges[i];
|
||||||
serialize8(adjRange->adjustmentIndex);
|
serialize8(adjRange->adjustmentIndex);
|
||||||
serialize8(adjRange->auxChannelIndex);
|
serialize8(adjRange->auxChannelIndex);
|
||||||
serialize8(adjRange->range.startStep);
|
serialize8(adjRange->range.startStep);
|
||||||
|
@ -900,7 +900,7 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
serialize8(masterConfig.rxConfig.rssi_channel);
|
serialize8(masterConfig.rxConfig.rssi_channel);
|
||||||
serialize8(0);
|
serialize8(0);
|
||||||
|
|
||||||
serialize16(currentProfile->mag_declination / 10);
|
serialize16(masterConfig.mag_declination / 10);
|
||||||
|
|
||||||
serialize8(masterConfig.batteryConfig.vbatscale);
|
serialize8(masterConfig.batteryConfig.vbatscale);
|
||||||
serialize8(masterConfig.batteryConfig.vbatmincellvoltage);
|
serialize8(masterConfig.batteryConfig.vbatmincellvoltage);
|
||||||
|
@ -973,8 +973,8 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
// Additional commands that are not compatible with MultiWii
|
// Additional commands that are not compatible with MultiWii
|
||||||
case MSP_ACC_TRIM:
|
case MSP_ACC_TRIM:
|
||||||
headSerialReply(4);
|
headSerialReply(4);
|
||||||
serialize16(currentProfile->accelerometerTrims.values.pitch);
|
serialize16(masterConfig.accelerometerTrims.values.pitch);
|
||||||
serialize16(currentProfile->accelerometerTrims.values.roll);
|
serialize16(masterConfig.accelerometerTrims.values.roll);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_UID:
|
case MSP_UID:
|
||||||
|
@ -1181,9 +1181,9 @@ static bool processOutCommand(uint8_t cmdMSP)
|
||||||
|
|
||||||
case MSP_RC_DEADBAND:
|
case MSP_RC_DEADBAND:
|
||||||
headSerialReply(3);
|
headSerialReply(3);
|
||||||
serialize8(currentProfile->rcControlsConfig.deadband);
|
serialize8(masterConfig.rcControlsConfig.deadband);
|
||||||
serialize8(currentProfile->rcControlsConfig.yaw_deadband);
|
serialize8(masterConfig.rcControlsConfig.yaw_deadband);
|
||||||
serialize8(currentProfile->rcControlsConfig.alt_hold_deadband);
|
serialize8(masterConfig.rcControlsConfig.alt_hold_deadband);
|
||||||
break;
|
break;
|
||||||
case MSP_SENSOR_ALIGNMENT:
|
case MSP_SENSOR_ALIGNMENT:
|
||||||
headSerialReply(3);
|
headSerialReply(3);
|
||||||
|
@ -1240,8 +1240,8 @@ static bool processInCommand(void)
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case MSP_SET_ACC_TRIM:
|
case MSP_SET_ACC_TRIM:
|
||||||
currentProfile->accelerometerTrims.values.pitch = read16();
|
masterConfig.accelerometerTrims.values.pitch = read16();
|
||||||
currentProfile->accelerometerTrims.values.roll = read16();
|
masterConfig.accelerometerTrims.values.roll = read16();
|
||||||
break;
|
break;
|
||||||
case MSP_SET_ARMING_CONFIG:
|
case MSP_SET_ARMING_CONFIG:
|
||||||
masterConfig.auto_disarm_delay = read8();
|
masterConfig.auto_disarm_delay = read8();
|
||||||
|
@ -1310,7 +1310,7 @@ static bool processInCommand(void)
|
||||||
case MSP_SET_MODE_RANGE:
|
case MSP_SET_MODE_RANGE:
|
||||||
i = read8();
|
i = read8();
|
||||||
if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
|
if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
|
||||||
modeActivationCondition_t *mac = ¤tProfile->modeActivationConditions[i];
|
modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
|
||||||
i = read8();
|
i = read8();
|
||||||
const box_t *box = findBoxByPermenantId(i);
|
const box_t *box = findBoxByPermenantId(i);
|
||||||
if (box) {
|
if (box) {
|
||||||
|
@ -1319,7 +1319,7 @@ static bool processInCommand(void)
|
||||||
mac->range.startStep = read8();
|
mac->range.startStep = read8();
|
||||||
mac->range.endStep = read8();
|
mac->range.endStep = read8();
|
||||||
|
|
||||||
useRcControlsConfig(currentProfile->modeActivationConditions, &masterConfig.escAndServoConfig, ¤tProfile->pidProfile);
|
useRcControlsConfig(masterConfig.modeActivationConditions, &masterConfig.escAndServoConfig, ¤tProfile->pidProfile);
|
||||||
} else {
|
} else {
|
||||||
headSerialError(0);
|
headSerialError(0);
|
||||||
}
|
}
|
||||||
|
@ -1330,7 +1330,7 @@ static bool processInCommand(void)
|
||||||
case MSP_SET_ADJUSTMENT_RANGE:
|
case MSP_SET_ADJUSTMENT_RANGE:
|
||||||
i = read8();
|
i = read8();
|
||||||
if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
|
if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
|
||||||
adjustmentRange_t *adjRange = ¤tProfile->adjustmentRanges[i];
|
adjustmentRange_t *adjRange = &masterConfig.adjustmentRanges[i];
|
||||||
i = read8();
|
i = read8();
|
||||||
if (i < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
|
if (i < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
|
||||||
adjRange->adjustmentIndex = i;
|
adjRange->adjustmentIndex = i;
|
||||||
|
@ -1391,7 +1391,7 @@ static bool processInCommand(void)
|
||||||
masterConfig.rxConfig.rssi_channel = read8();
|
masterConfig.rxConfig.rssi_channel = read8();
|
||||||
read8();
|
read8();
|
||||||
|
|
||||||
currentProfile->mag_declination = read16() * 10;
|
masterConfig.mag_declination = read16() * 10;
|
||||||
|
|
||||||
masterConfig.batteryConfig.vbatscale = read8(); // actual vbatscale as intended
|
masterConfig.batteryConfig.vbatscale = read8(); // actual vbatscale as intended
|
||||||
masterConfig.batteryConfig.vbatmincellvoltage = read8(); // vbatlevel_warn1 in MWC2.3 GUI
|
masterConfig.batteryConfig.vbatmincellvoltage = read8(); // vbatlevel_warn1 in MWC2.3 GUI
|
||||||
|
@ -1412,14 +1412,14 @@ static bool processInCommand(void)
|
||||||
if (i >= MAX_SUPPORTED_SERVOS) {
|
if (i >= MAX_SUPPORTED_SERVOS) {
|
||||||
headSerialError(0);
|
headSerialError(0);
|
||||||
} else {
|
} else {
|
||||||
currentProfile->servoConf[i].min = read16();
|
masterConfig.servoConf[i].min = read16();
|
||||||
currentProfile->servoConf[i].max = read16();
|
masterConfig.servoConf[i].max = read16();
|
||||||
currentProfile->servoConf[i].middle = read16();
|
masterConfig.servoConf[i].middle = read16();
|
||||||
currentProfile->servoConf[i].rate = read8();
|
masterConfig.servoConf[i].rate = read8();
|
||||||
currentProfile->servoConf[i].angleAtMin = read8();
|
masterConfig.servoConf[i].angleAtMin = read8();
|
||||||
currentProfile->servoConf[i].angleAtMax = read8();
|
masterConfig.servoConf[i].angleAtMax = read8();
|
||||||
currentProfile->servoConf[i].forwardFromChannel = read8();
|
masterConfig.servoConf[i].forwardFromChannel = read8();
|
||||||
currentProfile->servoConf[i].reversedSources = read32();
|
masterConfig.servoConf[i].reversedSources = read32();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
break;
|
break;
|
||||||
|
@ -1450,9 +1450,9 @@ static bool processInCommand(void)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_SET_RC_DEADBAND:
|
case MSP_SET_RC_DEADBAND:
|
||||||
currentProfile->rcControlsConfig.deadband = read8();
|
masterConfig.rcControlsConfig.deadband = read8();
|
||||||
currentProfile->rcControlsConfig.yaw_deadband = read8();
|
masterConfig.rcControlsConfig.yaw_deadband = read8();
|
||||||
currentProfile->rcControlsConfig.alt_hold_deadband = read8();
|
masterConfig.rcControlsConfig.alt_hold_deadband = read8();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case MSP_SET_RESET_CURR_PID:
|
case MSP_SET_RESET_CURR_PID:
|
||||||
|
|
|
@ -455,7 +455,7 @@ void init(void)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig,masterConfig.acc_hardware, masterConfig.mag_hardware, masterConfig.baro_hardware, currentProfile->mag_declination, masterConfig.gyro_lpf)) {
|
if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig,masterConfig.acc_hardware, masterConfig.mag_hardware, masterConfig.baro_hardware, masterConfig.mag_declination, masterConfig.gyro_lpf)) {
|
||||||
// if gyro was not detected due to whatever reason, we give up now.
|
// if gyro was not detected due to whatever reason, we give up now.
|
||||||
failureMode(FAILURE_MISSING_ACC);
|
failureMode(FAILURE_MISSING_ACC);
|
||||||
}
|
}
|
||||||
|
@ -490,7 +490,7 @@ void init(void)
|
||||||
|
|
||||||
failsafeInit(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle);
|
failsafeInit(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle);
|
||||||
|
|
||||||
rxInit(&masterConfig.rxConfig, currentProfile->modeActivationConditions);
|
rxInit(&masterConfig.rxConfig, masterConfig.modeActivationConditions);
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
if (feature(FEATURE_GPS)) {
|
if (feature(FEATURE_GPS)) {
|
||||||
|
@ -499,7 +499,7 @@ void init(void)
|
||||||
&masterConfig.gpsConfig
|
&masterConfig.gpsConfig
|
||||||
);
|
);
|
||||||
navigationInit(
|
navigationInit(
|
||||||
¤tProfile->gpsProfile,
|
&masterConfig.gpsProfile,
|
||||||
¤tProfile->pidProfile
|
¤tProfile->pidProfile
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
|
@ -129,8 +129,8 @@ extern pidControllerFuncPtr pid_controller;
|
||||||
|
|
||||||
void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsDelta)
|
void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t *rollAndPitchTrimsDelta)
|
||||||
{
|
{
|
||||||
currentProfile->accelerometerTrims.values.roll += rollAndPitchTrimsDelta->values.roll;
|
masterConfig.accelerometerTrims.values.roll += rollAndPitchTrimsDelta->values.roll;
|
||||||
currentProfile->accelerometerTrims.values.pitch += rollAndPitchTrimsDelta->values.pitch;
|
masterConfig.accelerometerTrims.values.pitch += rollAndPitchTrimsDelta->values.pitch;
|
||||||
|
|
||||||
saveConfigAndNotify();
|
saveConfigAndNotify();
|
||||||
}
|
}
|
||||||
|
@ -242,9 +242,9 @@ void annexCode(void)
|
||||||
for (axis = 0; axis < 3; axis++) {
|
for (axis = 0; axis < 3; axis++) {
|
||||||
tmp = MIN(ABS(rcData[axis] - masterConfig.rxConfig.midrc), 500);
|
tmp = MIN(ABS(rcData[axis] - masterConfig.rxConfig.midrc), 500);
|
||||||
if (axis == ROLL || axis == PITCH) {
|
if (axis == ROLL || axis == PITCH) {
|
||||||
if (currentProfile->rcControlsConfig.deadband) {
|
if (masterConfig.rcControlsConfig.deadband) {
|
||||||
if (tmp > currentProfile->rcControlsConfig.deadband) {
|
if (tmp > masterConfig.rcControlsConfig.deadband) {
|
||||||
tmp -= currentProfile->rcControlsConfig.deadband;
|
tmp -= masterConfig.rcControlsConfig.deadband;
|
||||||
} else {
|
} else {
|
||||||
tmp = 0;
|
tmp = 0;
|
||||||
}
|
}
|
||||||
|
@ -255,9 +255,9 @@ void annexCode(void)
|
||||||
prop1 = 100 - (uint16_t)currentControlRateProfile->rates[axis] * tmp / 500;
|
prop1 = 100 - (uint16_t)currentControlRateProfile->rates[axis] * tmp / 500;
|
||||||
prop1 = (uint16_t)prop1 * prop2 / 100;
|
prop1 = (uint16_t)prop1 * prop2 / 100;
|
||||||
} else if (axis == YAW) {
|
} else if (axis == YAW) {
|
||||||
if (currentProfile->rcControlsConfig.yaw_deadband) {
|
if (masterConfig.rcControlsConfig.yaw_deadband) {
|
||||||
if (tmp > currentProfile->rcControlsConfig.yaw_deadband) {
|
if (tmp > masterConfig.rcControlsConfig.yaw_deadband) {
|
||||||
tmp -= currentProfile->rcControlsConfig.yaw_deadband;
|
tmp -= masterConfig.rcControlsConfig.yaw_deadband;
|
||||||
} else {
|
} else {
|
||||||
tmp = 0;
|
tmp = 0;
|
||||||
}
|
}
|
||||||
|
@ -546,10 +546,10 @@ void processRx(void)
|
||||||
updateInflightCalibrationState();
|
updateInflightCalibrationState();
|
||||||
}
|
}
|
||||||
|
|
||||||
updateActivatedModes(currentProfile->modeActivationConditions);
|
updateActivatedModes(masterConfig.modeActivationConditions);
|
||||||
|
|
||||||
if (!cliMode) {
|
if (!cliMode) {
|
||||||
updateAdjustmentStates(currentProfile->adjustmentRanges);
|
updateAdjustmentStates(masterConfig.adjustmentRanges);
|
||||||
processRcAdjustments(currentControlRateProfile, &masterConfig.rxConfig);
|
processRcAdjustments(currentControlRateProfile, &masterConfig.rxConfig);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -689,8 +689,8 @@ void taskMainPidLoop(void)
|
||||||
rcCommand[YAW] = 0;
|
rcCommand[YAW] = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (currentProfile->throttle_correction_value && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) {
|
if (masterConfig.throttle_correction_value && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) {
|
||||||
rcCommand[THROTTLE] += calculateThrottleAngleCorrection(currentProfile->throttle_correction_value);
|
rcCommand[THROTTLE] += calculateThrottleAngleCorrection(masterConfig.throttle_correction_value);
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
|
@ -706,7 +706,7 @@ void taskMainPidLoop(void)
|
||||||
¤tProfile->pidProfile,
|
¤tProfile->pidProfile,
|
||||||
currentControlRateProfile,
|
currentControlRateProfile,
|
||||||
masterConfig.max_angle_inclination,
|
masterConfig.max_angle_inclination,
|
||||||
¤tProfile->accelerometerTrims,
|
&masterConfig.accelerometerTrims,
|
||||||
&masterConfig.rxConfig
|
&masterConfig.rxConfig
|
||||||
);
|
);
|
||||||
|
|
||||||
|
@ -753,7 +753,7 @@ void taskMainPidLoopCheck(void) {
|
||||||
|
|
||||||
void taskUpdateAccelerometer(void)
|
void taskUpdateAccelerometer(void)
|
||||||
{
|
{
|
||||||
imuUpdateAccelerometer(¤tProfile->accelerometerTrims);
|
imuUpdateAccelerometer(&masterConfig.accelerometerTrims);
|
||||||
}
|
}
|
||||||
|
|
||||||
void taskHandleSerial(void)
|
void taskHandleSerial(void)
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue