1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-20 14:55:18 +03:00

Merge pull request #1073 from martinbudden/inav_pg15_flight3DConfig

Added flight3DConfig parameter group
This commit is contained in:
Martin Budden 2017-01-10 09:29:43 +00:00 committed by GitHub
commit 90d03d114a
7 changed files with 38 additions and 45 deletions

View file

@ -49,8 +49,6 @@
#include "telemetry/telemetry.h"
#define flight3DConfig(x) (&masterConfig.flight3DConfig)
#define flight3DConfigMutable(x) (&masterConfig.flight3DConfig)
#define servoConfig(x) (&masterConfig.servoConfig)
#define servoConfigMutable(x) (&masterConfig.servoConfig)
#define servoMixerConfig(x) (&masterConfig.servoMixerConfig)
@ -95,8 +93,6 @@ typedef struct master_s {
uint8_t asyncMode;
#endif
flight3DConfig_t flight3DConfig;
#ifdef USE_SERVOS
servoConfig_t servoConfig;
servoMixerConfig_t servoMixerConfig;

View file

@ -41,7 +41,7 @@
//#define PG_PROFILE_SELECTION 23
#define PG_RX_CONFIG 24
//#define PG_RC_CONTROLS_CONFIG 25
//#define PG_MOTOR_3D_CONFIG 26
#define PG_MOTOR_3D_CONFIG 26
//#define PG_LED_STRIP_CONFIG 27
//#define PG_COLOR_CONFIG 28
//#define PG_AIRPLANE_ALT_HOLD_CONFIG 29

View file

@ -236,14 +236,6 @@ void resetServoConfig(servoConfig_t *servoConfig)
}
#endif
void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
{
flight3DConfig->deadband3d_low = 1406;
flight3DConfig->deadband3d_high = 1514;
flight3DConfig->neutral3d = 1460;
flight3DConfig->deadband3d_throttle = 50;
}
#ifdef TELEMETRY
void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
{
@ -422,8 +414,6 @@ void createDefaultConfig(master_t *config)
resetServoConfig(&config->servoConfig);
#endif
resetFlight3DConfig(&config->flight3DConfig);
#ifdef GPS
// gps/nav stuff
config->gpsConfig.provider = GPS_UBLOX;
@ -624,7 +614,6 @@ static void activateConfig(void)
setAccelerationCalibrationValues();
setAccelerationFilter();
mixerUseConfigs(&masterConfig.flight3DConfig);
#ifdef USE_SERVOS
servosUseConfigs(&masterConfig.servoMixerConfig, masterConfig.servoConf);
#endif
@ -638,7 +627,7 @@ static void activateConfig(void)
navigationUsePIDs(&currentProfile->pidProfile);
navigationUseRcControlsConfig(&masterConfig.rcControlsConfig);
navigationUseRxConfig(rxConfig());
navigationUseFlight3DConfig(&masterConfig.flight3DConfig);
navigationUseFlight3DConfig(flight3DConfig());
navigationUsemotorConfig(motorConfig());
#endif
}

View file

@ -545,7 +545,7 @@ void init(void)
&currentProfile->pidProfile,
&masterConfig.rcControlsConfig,
rxConfig(),
&masterConfig.flight3DConfig,
flight3DConfig(),
motorConfig()
);
#endif

View file

@ -611,6 +611,13 @@ static const clivalue_t valueTable[] = {
// PG_MIXER_CONFIG
{ "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, .config.minmax = { -1, 1 }, PG_MIXER_CONFIG, offsetof(mixerConfig_t, yaw_motor_direction) },
{ "yaw_jump_prevention_limit", VAR_UINT16 | MASTER_VALUE, .config.minmax = { YAW_JUMP_PREVENTION_LIMIT_LOW, YAW_JUMP_PREVENTION_LIMIT_HIGH }, PG_MIXER_CONFIG, offsetof(mixerConfig_t, yaw_jump_prevention_limit) },
// PG_MOTOR_3D_CONFIG
{ "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, deadband3d_low) }, // FIXME upper limit should match code in the mixer, 1500 currently
{ "3d_deadband_high", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, deadband3d_high) }, // FIXME lower limit should match code in the mixer, 1500 currently,
{ "3d_neutral", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, neutral3d) },
{ "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, deadband3d_throttle) },
};
#else
@ -633,11 +640,6 @@ const clivalue_t valueTable[] = {
{ "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &pwmRxConfig()->inputFilteringMode, .config.lookup = { TABLE_OFF_ON } },
{ "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, &flight3DConfig()->deadband3d_low, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME upper limit should match code in the mixer, 1500 currently
{ "3d_deadband_high", VAR_UINT16 | MASTER_VALUE, &flight3DConfig()->deadband3d_high, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME lower limit should match code in the mixer, 1500 currently,
{ "3d_neutral", VAR_UINT16 | MASTER_VALUE, &flight3DConfig()->neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &flight3DConfig()->deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "fixed_wing_auto_arm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &armingConfig()->fixed_wing_auto_arm, .config.lookup = { TABLE_OFF_ON } },
{ "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &armingConfig()->disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } },
{ "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &armingConfig()->auto_disarm_delay, .config.minmax = { 0, 60 } },
@ -1100,6 +1102,7 @@ static gimbalConfig_t gimbalConfigCopy;
#endif
static motorMixer_t customMotorMixerCopy[MAX_SUPPORTED_MOTORS];
static mixerConfig_t mixerConfigCopy;
static flight3DConfig_t flight3DConfigCopy;
static void backupConfigs(void)
{
@ -1131,6 +1134,7 @@ static void backupConfigs(void)
customMotorMixerCopy[ii] = *customMotorMixer(ii);
}
mixerConfigCopy = *mixerConfig();
flight3DConfigCopy = *flight3DConfig();
}
static void restoreConfigs(void)
@ -1162,6 +1166,7 @@ static void restoreConfigs(void)
*customMotorMixerMutable(ii) = customMotorMixerCopy[ii];
}
*mixerConfigMutable() = mixerConfigCopy;
*flight3DConfigMutable() = flight3DConfigCopy;
}
static void *getDefaultPointer(const void *valuePointer, const master_t *defaultConfig)
@ -1208,6 +1213,8 @@ static void dumpValues(uint16_t valueSection, uint8_t dumpMask, const master_t *
#ifdef USE_SERVOS
dumpPgValues(MASTER_VALUE, dumpMask, PG_GIMBAL_CONFIG, &gimbalConfigCopy, gimbalConfig());
#endif
dumpPgValues(MASTER_VALUE, dumpMask, PG_MIXER_CONFIG, &mixerConfigCopy, mixerConfig());
dumpPgValues(MASTER_VALUE, dumpMask, PG_MOTOR_3D_CONFIG, &flight3DConfigCopy, flight3DConfig());
return;
}
#endif

View file

@ -68,7 +68,15 @@ int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
bool motorLimitReached = false;
static flight3DConfig_t *flight3DConfig;
PG_REGISTER_WITH_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig, PG_MOTOR_3D_CONFIG, 0);
PG_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig,
.deadband3d_low = 1406,
.deadband3d_high = 1514,
.neutral3d = 1460,
.deadband3d_throttle = 50
);
PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 0);
@ -269,12 +277,6 @@ const mixer_t mixers[] = {
};
#endif // USE_QUAD_MIXER_ONLY
void mixerUseConfigs(
flight3DConfig_t *flight3DConfigToUse)
{
flight3DConfig = flight3DConfigToUse;
}
bool isMixerEnabled(mixerMode_e mixerMode)
{
#ifdef USE_QUAD_MIXER_ONLY
@ -362,7 +364,7 @@ void mixerResetDisarmedMotors(void)
int i;
// set disarmed motor values
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
motor_disarmed[i] = feature(FEATURE_3D) ? flight3DConfig->neutral3d : motorConfig()->mincommand;
motor_disarmed[i] = feature(FEATURE_3D) ? flight3DConfig()->neutral3d : motorConfig()->mincommand;
}
void writeMotors(void)
@ -385,7 +387,7 @@ void writeAllMotors(int16_t mc)
void stopMotors(void)
{
writeAllMotors(feature(FEATURE_3D) ? flight3DConfig->neutral3d : motorConfig()->mincommand);
writeAllMotors(feature(FEATURE_3D) ? flight3DConfig()->neutral3d : motorConfig()->mincommand);
delay(50); // give the timers and ESCs a chance to react.
}
@ -429,20 +431,20 @@ void mixTable(void)
if (feature(FEATURE_3D)) {
if (!ARMING_FLAG(ARMED)) throttlePrevious = rxConfig()->midrc; // When disarmed set to mid_rc. It always results in positive direction after arming.
if ((rcCommand[THROTTLE] <= (rxConfig()->midrc - flight3DConfig->deadband3d_throttle))) { // Out of band handling
throttleMax = flight3DConfig->deadband3d_low;
if ((rcCommand[THROTTLE] <= (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle))) { // Out of band handling
throttleMax = flight3DConfig()->deadband3d_low;
throttleMin = motorConfig()->minthrottle;
throttlePrevious = throttleCommand = rcCommand[THROTTLE];
} else if (rcCommand[THROTTLE] >= (rxConfig()->midrc + flight3DConfig->deadband3d_throttle)) { // Positive handling
} else if (rcCommand[THROTTLE] >= (rxConfig()->midrc + flight3DConfig()->deadband3d_throttle)) { // Positive handling
throttleMax = motorConfig()->maxthrottle;
throttleMin = flight3DConfig->deadband3d_high;
throttleMin = flight3DConfig()->deadband3d_high;
throttlePrevious = throttleCommand = rcCommand[THROTTLE];
} else if ((throttlePrevious <= (rxConfig()->midrc - flight3DConfig->deadband3d_throttle))) { // Deadband handling from negative to positive
throttleCommand = throttleMax = flight3DConfig->deadband3d_low;
} else if ((throttlePrevious <= (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle))) { // Deadband handling from negative to positive
throttleCommand = throttleMax = flight3DConfig()->deadband3d_low;
throttleMin = motorConfig()->minthrottle;
} else { // Deadband handling from positive to negative
throttleMax = motorConfig()->maxthrottle;
throttleCommand = throttleMin = flight3DConfig->deadband3d_high;
throttleCommand = throttleMin = flight3DConfig()->deadband3d_high;
}
} else {
throttleCommand = rcCommand[THROTTLE];
@ -481,10 +483,10 @@ void mixTable(void)
if (isFailsafeActive) {
motor[i] = constrain(motor[i], motorConfig()->mincommand, motorConfig()->maxthrottle);
} else if (feature(FEATURE_3D)) {
if (throttlePrevious <= (rxConfig()->midrc - flight3DConfig->deadband3d_throttle)) {
motor[i] = constrain(motor[i], motorConfig()->minthrottle, flight3DConfig->deadband3d_low);
if (throttlePrevious <= (rxConfig()->midrc - flight3DConfig()->deadband3d_throttle)) {
motor[i] = constrain(motor[i], motorConfig()->minthrottle, flight3DConfig()->deadband3d_low);
} else {
motor[i] = constrain(motor[i], flight3DConfig->deadband3d_high, motorConfig()->maxthrottle);
motor[i] = constrain(motor[i], flight3DConfig()->deadband3d_high, motorConfig()->maxthrottle);
}
} else {
motor[i] = constrain(motor[i], motorConfig()->minthrottle, motorConfig()->maxthrottle);

View file

@ -106,15 +106,14 @@ typedef struct flight3DConfig_s {
uint16_t deadband3d_throttle; // default throttle deadband from MIDRC
} flight3DConfig_t;
PG_DECLARE(flight3DConfig_t, flight3DConfig);
#define CHANNEL_FORWARDING_DISABLED (uint8_t)0xFF
extern int16_t motor[MAX_SUPPORTED_MOTORS];
extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS];
extern bool motorLimitReached;
void mixerUseConfigs(
flight3DConfig_t *flight3DConfigToUse);
void writeAllMotors(int16_t mc);
void mixerLoadMix(int index, motorMixer_t *customMixers);
void mixerUsePWMIOConfiguration(void);