mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-23 00:05:28 +03:00
Fixup after rebase
This commit is contained in:
parent
a23ad505d4
commit
03e10ff57a
8 changed files with 19 additions and 21 deletions
|
@ -259,11 +259,13 @@ void resetMotorConfig(motorConfig_t *motorConfig)
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void resetServoConfig(servoConfig_t *servoConfig)
|
#ifdef USE_SERVOS
|
||||||
|
void resetServoPwmConfig(servoPwmConfig_t *servoPwmConfig)
|
||||||
{
|
{
|
||||||
servoConfig->servoCenterPulse = 1500;
|
servoPwmConfig->servoCenterPulse = 1500;
|
||||||
servoConfig->servoPwmRate = 50;
|
servoPwmConfig->servoPwmRate = 50;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
|
void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
|
||||||
{
|
{
|
||||||
|
@ -487,11 +489,10 @@ static void resetConf(void)
|
||||||
resetMixerConfig(&masterConfig.mixerConfig);
|
resetMixerConfig(&masterConfig.mixerConfig);
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
resetServoConfig(&masterConfig.servoConfig);
|
resetServoConfig(&masterConfig.servoConfig);
|
||||||
|
resetServoPwmConfig(&masterConfig.servoPwmConfig);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Motor/ESC/Servo
|
|
||||||
resetMotorConfig(&masterConfig.motorConfig);
|
resetMotorConfig(&masterConfig.motorConfig);
|
||||||
resetServoConfig(&masterConfig.servoConfig);
|
|
||||||
resetFlight3DConfig(&masterConfig.flight3DConfig);
|
resetFlight3DConfig(&masterConfig.flight3DConfig);
|
||||||
|
|
||||||
#ifdef GPS
|
#ifdef GPS
|
||||||
|
@ -728,7 +729,7 @@ void activateConfig(void)
|
||||||
|
|
||||||
mixerUseConfigs(&masterConfig.flight3DConfig, &masterConfig.motorConfig, &masterConfig.mixerConfig, &masterConfig.rxConfig);
|
mixerUseConfigs(&masterConfig.flight3DConfig, &masterConfig.motorConfig, &masterConfig.mixerConfig, &masterConfig.rxConfig);
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
servosUseConfigs(&masterConfig.servoConfig, currentProfile->servoConf, ¤tProfile->gimbalConfig);
|
servosUseConfigs(&masterConfig.servoConfig, currentProfile->servoConf, ¤tProfile->gimbalConfig, &masterConfig.rxConfig);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
imuRuntimeConfig.dcm_kp_acc = masterConfig.dcm_kp_acc / 10000.0f;
|
imuRuntimeConfig.dcm_kp_acc = masterConfig.dcm_kp_acc / 10000.0f;
|
||||||
|
|
|
@ -37,7 +37,7 @@ typedef struct master_s {
|
||||||
#endif
|
#endif
|
||||||
// motor/esc/servo related stuff
|
// motor/esc/servo related stuff
|
||||||
motorConfig_t motorConfig;
|
motorConfig_t motorConfig;
|
||||||
servoConfig_t servoConfig;
|
servoPwmConfig_t servoPwmConfig;
|
||||||
flight3DConfig_t flight3DConfig;
|
flight3DConfig_t flight3DConfig;
|
||||||
|
|
||||||
// global sensor-related stuff
|
// global sensor-related stuff
|
||||||
|
|
|
@ -73,13 +73,8 @@ bool motorLimitReached = false;
|
||||||
|
|
||||||
mixerConfig_t *mixerConfig;
|
mixerConfig_t *mixerConfig;
|
||||||
static flight3DConfig_t *flight3DConfig;
|
static flight3DConfig_t *flight3DConfig;
|
||||||
<<<<<<< 8e828b19d6c2105114ebe7dfa31f114733ca326d
|
|
||||||
static escAndServoConfig_t *escAndServoConfig;
|
|
||||||
rxConfig_t *rxConfig;
|
|
||||||
=======
|
|
||||||
static motorConfig_t *motorConfig;
|
static motorConfig_t *motorConfig;
|
||||||
static rxConfig_t *rxConfig;
|
static rxConfig_t *rxConfig;
|
||||||
>>>>>>> Split escAndServoConfig into motor and servo parts, as per betaflight
|
|
||||||
|
|
||||||
mixerMode_e currentMixerMode;
|
mixerMode_e currentMixerMode;
|
||||||
static motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS];
|
static motorMixer_t currentMixer[MAX_SUPPORTED_MOTORS];
|
||||||
|
|
|
@ -63,7 +63,8 @@
|
||||||
extern mixerMode_e currentMixerMode;
|
extern mixerMode_e currentMixerMode;
|
||||||
extern const mixer_t mixers[];
|
extern const mixer_t mixers[];
|
||||||
extern mixerConfig_t *mixerConfig;
|
extern mixerConfig_t *mixerConfig;
|
||||||
extern rxConfig_t *rxConfig;
|
|
||||||
|
static rxConfig_t *rxConfig;
|
||||||
|
|
||||||
servoConfig_t *servoConfig;
|
servoConfig_t *servoConfig;
|
||||||
|
|
||||||
|
@ -134,11 +135,12 @@ const mixerRules_t servoMixers[] = {
|
||||||
|
|
||||||
static servoMixer_t *customServoMixers;
|
static servoMixer_t *customServoMixers;
|
||||||
|
|
||||||
void servosUseConfigs(servoConfig_t *servoConfigToUse, servoParam_t *servoParamsToUse, gimbalConfig_t *gimbalConfigToUse)
|
void servosUseConfigs(servoConfig_t *servoConfigToUse, servoParam_t *servoParamsToUse, gimbalConfig_t *gimbalConfigToUse, rxConfig_t *rxConfigToUse)
|
||||||
{
|
{
|
||||||
servoConfig = servoConfigToUse;
|
servoConfig = servoConfigToUse;
|
||||||
servoConf = servoParamsToUse;
|
servoConf = servoParamsToUse;
|
||||||
gimbalConfig = gimbalConfigToUse;
|
gimbalConfig = gimbalConfigToUse;
|
||||||
|
rxConfig = rxConfigToUse;
|
||||||
}
|
}
|
||||||
|
|
||||||
int16_t getFlaperonDirection(uint8_t servoPin) {
|
int16_t getFlaperonDirection(uint8_t servoPin) {
|
||||||
|
|
|
@ -127,6 +127,6 @@ void filterServos(void);
|
||||||
void servoMixerLoadMix(int index, servoMixer_t *customServoMixers);
|
void servoMixerLoadMix(int index, servoMixer_t *customServoMixers);
|
||||||
void loadCustomServoMixer(void);
|
void loadCustomServoMixer(void);
|
||||||
int servoDirection(int servoIndex, int fromChannel);
|
int servoDirection(int servoIndex, int fromChannel);
|
||||||
void servosUseConfigs(servoConfig_t *servoConfigToUse, servoParam_t *servoParamsToUse, gimbalConfig_t *gimbalConfigToUse);
|
void servosUseConfigs(servoConfig_t *servoConfigToUse, servoParam_t *servoParamsToUse, gimbalConfig_t *gimbalConfigToUse, struct rxConfig_s *rxConfigToUse);
|
||||||
void servosInit(servoMixer_t *customServoMixers);
|
void servosInit(servoMixer_t *customServoMixers);
|
||||||
|
|
||||||
|
|
|
@ -760,8 +760,8 @@ const clivalue_t valueTable[] = {
|
||||||
{ "servo_lowpass_freq", VAR_INT16 | MASTER_VALUE, &masterConfig.servoConfig.servo_lowpass_freq, .config.minmax = { 10, 400}, 0 },
|
{ "servo_lowpass_freq", VAR_INT16 | MASTER_VALUE, &masterConfig.servoConfig.servo_lowpass_freq, .config.minmax = { 10, 400}, 0 },
|
||||||
{ "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.servoConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON }, 0 },
|
{ "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.servoConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON }, 0 },
|
||||||
{ "gimbal_mode", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].gimbalConfig.mode, .config.lookup = { TABLE_GIMBAL_MODE }, 0 },
|
{ "gimbal_mode", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].gimbalConfig.mode, .config.lookup = { TABLE_GIMBAL_MODE }, 0 },
|
||||||
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.servoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 },
|
{ "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.servoPwmConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 },
|
||||||
{ "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servoConfig.servoPwmRate, .config.minmax = { 50, 498 }, 0 },
|
{ "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servoPwmConfig.servoPwmRate, .config.minmax = { 50, 498 }, 0 },
|
||||||
{ "fw_iterm_throw_limit", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.fixedWingItermThrowLimit, .config.minmax = { FW_ITERM_THROW_LIMIT_MIN, FW_ITERM_THROW_LIMIT_MAX}, 0 },
|
{ "fw_iterm_throw_limit", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.fixedWingItermThrowLimit, .config.minmax = { FW_ITERM_THROW_LIMIT_MIN, FW_ITERM_THROW_LIMIT_MAX}, 0 },
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -17,8 +17,8 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
typedef struct servoConfig_s {
|
typedef struct servoPwmConfig_s {
|
||||||
// PWM values, in milliseconds, common range is 1000-2000 (1ms to 2ms)
|
// PWM values, in milliseconds, common range is 1000-2000 (1ms to 2ms)
|
||||||
uint16_t servoCenterPulse; // This is the value for servos when they should be in the middle. e.g. 1500.
|
uint16_t servoCenterPulse; // This is the value for servos when they should be in the middle. e.g. 1500.
|
||||||
uint16_t servoPwmRate; // The update rate of servo outputs (50-498Hz)
|
uint16_t servoPwmRate; // The update rate of servo outputs (50-498Hz)
|
||||||
} servoConfig_t;
|
} servoPwmConfig_t;
|
||||||
|
|
|
@ -270,8 +270,8 @@ void init(void)
|
||||||
#ifdef USE_SERVOS
|
#ifdef USE_SERVOS
|
||||||
pwm_params.useServos = isMixerUsingServos();
|
pwm_params.useServos = isMixerUsingServos();
|
||||||
pwm_params.useChannelForwarding = feature(FEATURE_CHANNEL_FORWARDING);
|
pwm_params.useChannelForwarding = feature(FEATURE_CHANNEL_FORWARDING);
|
||||||
pwm_params.servoCenterPulse = masterConfig.servoConfig.servoCenterPulse;
|
pwm_params.servoCenterPulse = masterConfig.servoPwmConfig.servoCenterPulse;
|
||||||
pwm_params.servoPwmRate = masterConfig.servoConfig.servoPwmRate;
|
pwm_params.servoPwmRate = masterConfig.servoPwmConfig.servoPwmRate;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
pwm_params.useOneshot = feature(FEATURE_ONESHOT125);
|
pwm_params.useOneshot = feature(FEATURE_ONESHOT125);
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue