Moving mixer config out of the profile. It doesn't really make sense.
This commit is contained in:
parent
ed434fe47b
commit
4a12d00d1e
|
@ -119,7 +119,7 @@ profile_t *currentProfile;
|
||||||
static uint8_t currentControlRateProfileIndex = 0;
|
static uint8_t currentControlRateProfileIndex = 0;
|
||||||
controlRateConfig_t *currentControlRateProfile;
|
controlRateConfig_t *currentControlRateProfile;
|
||||||
|
|
||||||
static const uint8_t EEPROM_CONF_VERSION = 93;
|
static const uint8_t EEPROM_CONF_VERSION = 94;
|
||||||
|
|
||||||
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
||||||
{
|
{
|
||||||
|
@ -293,6 +293,16 @@ void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) {
|
||||||
rcControlsConfig->alt_hold_fast_change = 1;
|
rcControlsConfig->alt_hold_fast_change = 1;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void resetMixerConfig(mixerConfig_t *mixerConfig) {
|
||||||
|
mixerConfig->pid_at_min_throttle = 1;
|
||||||
|
mixerConfig->yaw_direction = 1;
|
||||||
|
#ifdef USE_SERVOS
|
||||||
|
mixerConfig->tri_unarmed_servo = 1;
|
||||||
|
mixerConfig->servo_lowpass_freq = 400;
|
||||||
|
mixerConfig->servo_lowpass_enable = 0;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
uint8_t getCurrentProfile(void)
|
uint8_t getCurrentProfile(void)
|
||||||
{
|
{
|
||||||
return masterConfig.current_profile_index;
|
return masterConfig.current_profile_index;
|
||||||
|
@ -378,8 +388,8 @@ static void resetConf(void)
|
||||||
masterConfig.disarm_kill_switch = 1;
|
masterConfig.disarm_kill_switch = 1;
|
||||||
masterConfig.auto_disarm_delay = 5;
|
masterConfig.auto_disarm_delay = 5;
|
||||||
masterConfig.small_angle = 25;
|
masterConfig.small_angle = 25;
|
||||||
masterConfig.pid_at_min_throttle = 1;
|
|
||||||
|
|
||||||
|
resetMixerConfig(&masterConfig.mixerConfig);
|
||||||
|
|
||||||
masterConfig.airplaneConfig.flaps_speed = 0;
|
masterConfig.airplaneConfig.flaps_speed = 0;
|
||||||
masterConfig.airplaneConfig.fixedwing_althold_dir = 1;
|
masterConfig.airplaneConfig.fixedwing_althold_dir = 1;
|
||||||
|
@ -452,11 +462,6 @@ static void resetConf(void)
|
||||||
currentProfile->servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
|
currentProfile->servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
|
||||||
}
|
}
|
||||||
|
|
||||||
currentProfile->mixerConfig.yaw_direction = 1;
|
|
||||||
currentProfile->mixerConfig.tri_unarmed_servo = 1;
|
|
||||||
currentProfile->mixerConfig.servo_lowpass_freq = 400;
|
|
||||||
currentProfile->mixerConfig.servo_lowpass_enable = 0;
|
|
||||||
|
|
||||||
// gimbal
|
// gimbal
|
||||||
currentProfile->gimbalConfig.gimbal_flags = GIMBAL_NORMAL;
|
currentProfile->gimbalConfig.gimbal_flags = GIMBAL_NORMAL;
|
||||||
#endif
|
#endif
|
||||||
|
@ -648,7 +653,7 @@ void activateConfig(void)
|
||||||
#endif
|
#endif
|
||||||
&masterConfig.flight3DConfig,
|
&masterConfig.flight3DConfig,
|
||||||
&masterConfig.escAndServoConfig,
|
&masterConfig.escAndServoConfig,
|
||||||
¤tProfile->mixerConfig,
|
&masterConfig.mixerConfig,
|
||||||
&masterConfig.airplaneConfig,
|
&masterConfig.airplaneConfig,
|
||||||
&masterConfig.rxConfig
|
&masterConfig.rxConfig
|
||||||
);
|
);
|
||||||
|
|
|
@ -65,7 +65,9 @@ typedef struct master_t {
|
||||||
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
|
||||||
uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
|
uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
|
||||||
uint8_t small_angle;
|
uint8_t small_angle;
|
||||||
uint8_t pid_at_min_throttle; // when enabled pids are used at minimum throttle
|
|
||||||
|
// mixer-related configuration
|
||||||
|
mixerConfig_t mixerConfig;
|
||||||
|
|
||||||
airplaneConfig_t airplaneConfig;
|
airplaneConfig_t airplaneConfig;
|
||||||
|
|
||||||
|
|
|
@ -57,9 +57,6 @@ typedef struct profile_s {
|
||||||
// Failsafe related configuration
|
// Failsafe related configuration
|
||||||
failsafeConfig_t failsafeConfig;
|
failsafeConfig_t failsafeConfig;
|
||||||
|
|
||||||
// mixer-related configuration
|
|
||||||
mixerConfig_t mixerConfig;
|
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
gpsProfile_t gpsProfile;
|
gpsProfile_t gpsProfile;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -25,17 +25,14 @@
|
||||||
|
|
||||||
#include "common/axis.h"
|
#include "common/axis.h"
|
||||||
#include "common/maths.h"
|
#include "common/maths.h"
|
||||||
#include "common/color.h"
|
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/gpio.h"
|
#include "drivers/gpio.h"
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
#include "drivers/pwm_output.h"
|
#include "drivers/pwm_output.h"
|
||||||
#include "drivers/pwm_mapping.h"
|
#include "drivers/pwm_mapping.h"
|
||||||
#include "drivers/pwm_rx.h"
|
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/accgyro.h"
|
#include "drivers/accgyro.h"
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
|
||||||
#include "rx/rx.h"
|
#include "rx/rx.h"
|
||||||
|
@ -43,30 +40,17 @@
|
||||||
#include "io/gimbal.h"
|
#include "io/gimbal.h"
|
||||||
#include "io/escservo.h"
|
#include "io/escservo.h"
|
||||||
#include "io/rc_controls.h"
|
#include "io/rc_controls.h"
|
||||||
#include "io/gps.h"
|
|
||||||
#include "io/serial.h"
|
|
||||||
#include "io/ledstrip.h"
|
|
||||||
|
|
||||||
#include "sensors/sensors.h"
|
#include "sensors/sensors.h"
|
||||||
#include "sensors/acceleration.h"
|
#include "sensors/acceleration.h"
|
||||||
#include "sensors/boardalignment.h"
|
|
||||||
#include "sensors/gyro.h"
|
|
||||||
#include "sensors/battery.h"
|
|
||||||
#include "sensors/barometer.h"
|
|
||||||
|
|
||||||
#include "flight/mixer.h"
|
#include "flight/mixer.h"
|
||||||
#include "flight/pid.h"
|
#include "flight/pid.h"
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
#include "flight/lowpass.h"
|
#include "flight/lowpass.h"
|
||||||
#include "flight/failsafe.h"
|
|
||||||
#include "flight/navigation.h"
|
|
||||||
|
|
||||||
#include "telemetry/telemetry.h"
|
|
||||||
|
|
||||||
#include "config/runtime_config.h"
|
#include "config/runtime_config.h"
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
#include "config/config_profile.h"
|
|
||||||
#include "config/config_master.h"
|
|
||||||
|
|
||||||
#define GIMBAL_SERVO_PITCH 0
|
#define GIMBAL_SERVO_PITCH 0
|
||||||
#define GIMBAL_SERVO_ROLL 1
|
#define GIMBAL_SERVO_ROLL 1
|
||||||
|
@ -718,7 +702,7 @@ void mixTable(void)
|
||||||
if ((rcData[THROTTLE]) < rxConfig->mincheck) {
|
if ((rcData[THROTTLE]) < rxConfig->mincheck) {
|
||||||
if (feature(FEATURE_MOTOR_STOP)) {
|
if (feature(FEATURE_MOTOR_STOP)) {
|
||||||
motor[i] = escAndServoConfig->mincommand;
|
motor[i] = escAndServoConfig->mincommand;
|
||||||
} else if (masterConfig.pid_at_min_throttle == 0) {
|
} else if (mixerConfig->pid_at_min_throttle == 0) {
|
||||||
motor[i] = escAndServoConfig->minthrottle;
|
motor[i] = escAndServoConfig->minthrottle;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -64,6 +64,7 @@ typedef struct mixer_t {
|
||||||
} mixer_t;
|
} mixer_t;
|
||||||
|
|
||||||
typedef struct mixerConfig_s {
|
typedef struct mixerConfig_s {
|
||||||
|
uint8_t pid_at_min_throttle; // when enabled pids are used at minimum throttle
|
||||||
int8_t yaw_direction;
|
int8_t yaw_direction;
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
uint8_t tri_unarmed_servo; // send tail servo correction pulses even when unarmed
|
uint8_t tri_unarmed_servo; // send tail servo correction pulses even when unarmed
|
||||||
|
|
|
@ -274,7 +274,6 @@ const clivalue_t valueTable[] = {
|
||||||
{ "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.disarm_kill_switch, 0, 1 },
|
{ "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.disarm_kill_switch, 0, 1 },
|
||||||
{ "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, 0, 60 },
|
{ "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, 0, 60 },
|
||||||
{ "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, 0, 180 },
|
{ "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, 0, 180 },
|
||||||
{ "pid_at_min_throttle", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_at_min_throttle, 0, 1 },
|
|
||||||
|
|
||||||
{ "flaps_speed", VAR_UINT8 | MASTER_VALUE, &masterConfig.airplaneConfig.flaps_speed, 0, 100 },
|
{ "flaps_speed", VAR_UINT8 | MASTER_VALUE, &masterConfig.airplaneConfig.flaps_speed, 0, 100 },
|
||||||
|
|
||||||
|
@ -382,12 +381,15 @@ const clivalue_t valueTable[] = {
|
||||||
{ "throttle_correction_angle", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].throttle_correction_angle, 1, 900 },
|
{ "throttle_correction_angle", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].throttle_correction_angle, 1, 900 },
|
||||||
|
|
||||||
{ "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, -1, 1 },
|
{ "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, -1, 1 },
|
||||||
{ "yaw_direction", VAR_INT8 | PROFILE_VALUE, &masterConfig.profile[0].mixerConfig.yaw_direction, -1, 1 },
|
|
||||||
|
{ "pid_at_min_throttle", VAR_UINT8 | MASTER_VALUE, &masterConfig.mixerConfig.pid_at_min_throttle, 0, 1 },
|
||||||
|
{ "yaw_direction", VAR_INT8 | PROFILE_VALUE, &masterConfig.mixerConfig.yaw_direction, -1, 1 },
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
{ "tri_unarmed_servo", VAR_INT8 | PROFILE_VALUE, &masterConfig.profile[0].mixerConfig.tri_unarmed_servo, 0, 1 },
|
{ "tri_unarmed_servo", VAR_INT8 | PROFILE_VALUE, &masterConfig.mixerConfig.tri_unarmed_servo, 0, 1 },
|
||||||
{ "servo_lowpass_freq", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].mixerConfig.servo_lowpass_freq, 10, 400},
|
{ "servo_lowpass_freq", VAR_INT16 | PROFILE_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, 10, 400},
|
||||||
{ "servo_lowpass_enable", VAR_INT8 | PROFILE_VALUE, &masterConfig.profile[0].mixerConfig.servo_lowpass_enable, 0, 1 },
|
{ "servo_lowpass_enable", VAR_INT8 | PROFILE_VALUE, &masterConfig.mixerConfig.servo_lowpass_enable, 0, 1 },
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
{ "default_rate_profile", VAR_UINT8 | PROFILE_VALUE , &masterConfig.profile[0].defaultRateProfileIndex, 0, MAX_CONTROL_RATE_PROFILE_COUNT - 1 },
|
{ "default_rate_profile", VAR_UINT8 | PROFILE_VALUE , &masterConfig.profile[0].defaultRateProfileIndex, 0, MAX_CONTROL_RATE_PROFILE_COUNT - 1 },
|
||||||
{ "rc_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcRate8, 0, 250 },
|
{ "rc_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcRate8, 0, 250 },
|
||||||
{ "rc_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcExpo8, 0, 100 },
|
{ "rc_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcExpo8, 0, 100 },
|
||||||
|
|
Loading…
Reference in New Issue