Seperate ONESHOT125 feature from fast_pwm_protocol

This commit is contained in:
borisbstyle 2016-05-24 23:10:09 +02:00
parent 80e047e651
commit f1d422c322
8 changed files with 18 additions and 13 deletions

View File

@ -486,7 +486,7 @@ static void resetConf(void)
masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
#endif
masterConfig.servo_pwm_rate = 50;
masterConfig.fast_pwm_protocol = 0;
masterConfig.fast_pwm_protocol = 1;
masterConfig.use_unsyncedPwm = 0;
#ifdef CC3D
masterConfig.use_buzzer_p6 = 0;

View File

@ -34,7 +34,7 @@ typedef struct master_t {
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)
uint8_t fast_pwm_protocol; // Fast Pwm Protocol
uint8_t fast_pwm_protocol; // Pwm Protocol
uint8_t use_unsyncedPwm; // unsync fast pwm protocol from PID loop
#ifdef USE_SERVOS

View File

@ -929,7 +929,7 @@ if (init->useBuzzerP6) {
}
#endif
if (init->useFastPwm) {
pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->fastPwmProtocolType, init->motorPwmRate, init->useUnsyncedPwm, init->idlePulse);
pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->pwmProtocolType, init->motorPwmRate, init->useUnsyncedPwm, init->idlePulse);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ;
} else if (isMotorBrushed(init->motorPwmRate)) {
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);

View File

@ -71,7 +71,7 @@ typedef struct drv_pwm_config_s {
#ifdef USE_SERVOS
bool useServos;
bool useChannelForwarding; // configure additional channels as servos
uint8_t fastPwmProtocolType;
uint8_t pwmProtocolType;
uint16_t servoPwmRate;
uint16_t servoCenterPulse;
#endif

View File

@ -18,9 +18,10 @@
#pragma once
typedef enum {
PWM_TYPE_ONESHOT125 = 0,
PWM_TYPE_ONESHOT42 = 1,
PWM_TYPE_MULTISHOT = 2
PWM_TYPE_CONVENTIONAL = 0,
PWM_TYPE_ONESHOT125,
PWM_TYPE_ONESHOT42,
PWM_TYPE_MULTISHOT
} FastPwmProtocolTypes_e;
void pwmWriteMotor(uint8_t index, uint16_t value);

View File

@ -443,7 +443,7 @@ static const char * const lookupTableSuperExpoYaw[] = {
};
static const char * const lookupTableFastPwm[] = {
"ONESHOT125", "ONESHOT42", "MULTISHOT"
"OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT"
};
typedef struct lookupTableEntry_s {

View File

@ -171,9 +171,6 @@ void setGyroSamplingSpeed(uint16_t looptime) {
masterConfig.pid_process_denom = 1;
}
#endif
// Oneshot125 protection
if ((masterConfig.fast_pwm_protocol == 0) && ((masterConfig.gyro_sync_denom * gyroSampleRate) == 125) && masterConfig.pid_process_denom < 3) masterConfig.pid_process_denom = 3;
}
}

View File

@ -44,6 +44,7 @@
#include "drivers/compass.h"
#include "drivers/pwm_mapping.h"
#include "drivers/pwm_rx.h"
#include "drivers/pwm_output.h"
#include "drivers/adc.h"
#include "drivers/bus_i2c.h"
#include "drivers/bus_bst.h"
@ -311,8 +312,14 @@ void init(void)
pwm_params.servoPwmRate = masterConfig.servo_pwm_rate;
#endif
pwm_params.useFastPwm = feature(FEATURE_ONESHOT125); // Configurator feature abused for enabling Fast PWM
pwm_params.fastPwmProtocolType = masterConfig.fast_pwm_protocol;
if (masterConfig.fast_pwm_protocol == PWM_TYPE_ONESHOT125) {
featureSet(FEATURE_ONESHOT125);
} else {
featureClear(FEATURE_ONESHOT125);
}
pwm_params.useFastPwm = (masterConfig.fast_pwm_protocol != PWM_TYPE_CONVENTIONAL) ? true : false; // Configurator feature abused for enabling Fast PWM
pwm_params.pwmProtocolType = masterConfig.fast_pwm_protocol;
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;
pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand;
pwm_params.useUnsyncedPwm = masterConfig.use_unsyncedPwm;