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

Move motor and servo params out of master_t

This commit is contained in:
Martin Budden 2016-10-01 22:34:25 +01:00
parent f57c22f2a2
commit 7aac652b62
6 changed files with 10 additions and 14 deletions

View file

@ -249,16 +249,20 @@ void resetMotorConfig(motorConfig_t *motorConfig)
{ {
#ifdef BRUSHED_MOTORS #ifdef BRUSHED_MOTORS
motorConfig->minthrottle = 1000; motorConfig->minthrottle = 1000;
motorConfig->motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
#else #else
motorConfig->minthrottle = 1150; motorConfig->minthrottle = 1150;
motorConfig->motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
#endif #endif
motorConfig->maxthrottle = 1850; motorConfig->maxthrottle = 1850;
motorConfig->mincommand = 1000; motorConfig->mincommand = 1000;
} }
void resetServoConfig(servoConfig_t *servoConfig) void resetServoConfig(servoConfig_t *servoConfig)
{ {
servoConfig->servoCenterPulse = 1500; servoConfig->servoCenterPulse = 1500;
servoConfig->servoPwmRate = 50;
} }
void resetFlight3DConfig(flight3DConfig_t *flight3DConfig) void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
@ -490,13 +494,6 @@ static void resetConf(void)
resetServoConfig(&masterConfig.servoConfig); resetServoConfig(&masterConfig.servoConfig);
resetFlight3DConfig(&masterConfig.flight3DConfig); resetFlight3DConfig(&masterConfig.flight3DConfig);
#ifdef BRUSHED_MOTORS
masterConfig.motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE;
#else
masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
#endif
masterConfig.servo_pwm_rate = 50;
#ifdef GPS #ifdef GPS
// gps/nav stuff // gps/nav stuff
masterConfig.gpsConfig.provider = GPS_UBLOX; masterConfig.gpsConfig.provider = GPS_UBLOX;

View file

@ -40,9 +40,6 @@ typedef struct master_s {
servoConfig_t servoConfig; servoConfig_t servoConfig;
flight3DConfig_t flight3DConfig; flight3DConfig_t flight3DConfig;
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)
// global sensor-related stuff // global sensor-related stuff
sensorAlignmentConfig_t sensorAlignmentConfig; sensorAlignmentConfig_t sensorAlignmentConfig;

View file

@ -22,4 +22,5 @@ typedef struct motorConfig_s {
uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed. uint16_t minthrottle; // Set the minimum throttle command sent to the ESC (Electronic Speed Controller). This is the minimum value that allow motors to run at a idle speed.
uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000 uint16_t maxthrottle; // This is the maximum value for the ESCs at full power this value can be increased up to 2000
uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs uint16_t mincommand; // This is the value for the ESCs when they are not armed. In some cases, this value must be lowered down to 900 for some specific ESCs
uint16_t motorPwmRate; // The update rate of motor outputs (50-498Hz)
} motorConfig_t; } motorConfig_t;

View file

@ -604,7 +604,7 @@ const clivalue_t valueTable[] = {
{ "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 }, { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 },
{ "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 }, { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 },
{ "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 50, 32000 }, 0 }, { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motorConfig.motorPwmRate, .config.minmax = { 50, 32000 }, 0 },
{ "fixed_wing_auto_arm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.fixed_wing_auto_arm, .config.lookup = { TABLE_OFF_ON }, 0 }, { "fixed_wing_auto_arm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.fixed_wing_auto_arm, .config.lookup = { TABLE_OFF_ON }, 0 },
{ "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON }, 0 }, { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON }, 0 },
@ -761,7 +761,7 @@ const clivalue_t valueTable[] = {
{ "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.servoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 },
{ "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, .config.minmax = { 50, 498 }, 0 }, { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servoConfig.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

View file

@ -20,4 +20,5 @@
typedef struct servoConfig_s { typedef struct servoConfig_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)
} servoConfig_t; } servoConfig_t;

View file

@ -271,11 +271,11 @@ void init(void)
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.servoConfig.servoCenterPulse;
pwm_params.servoPwmRate = masterConfig.servo_pwm_rate; pwm_params.servoPwmRate = masterConfig.servoConfig.servoPwmRate;
#endif #endif
pwm_params.useOneshot = feature(FEATURE_ONESHOT125); pwm_params.useOneshot = feature(FEATURE_ONESHOT125);
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate; pwm_params.motorPwmRate = masterConfig.motorConfig.motorPwmRate;
pwm_params.idlePulse = masterConfig.motorConfig.mincommand; pwm_params.idlePulse = masterConfig.motorConfig.mincommand;
if (feature(FEATURE_3D)) if (feature(FEATURE_3D))
pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d; pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d;