Oneshot42 Implementation

This commit is contained in:
borisbstyle 2016-02-22 15:13:36 +01:00
parent e561ec3cb7
commit 6b8f4f1111
7 changed files with 33 additions and 11 deletions

View File

@ -484,6 +484,7 @@ static void resetConf(void)
#endif #endif
masterConfig.servo_pwm_rate = 50; masterConfig.servo_pwm_rate = 50;
masterConfig.use_fast_pwm = 0; masterConfig.use_fast_pwm = 0;
masterConfig.use_oneshot42 = 0;
#ifdef CC3D #ifdef CC3D
masterConfig.use_buzzer_p6 = 0; masterConfig.use_buzzer_p6 = 0;
#endif #endif

View File

@ -37,6 +37,7 @@ typedef struct master_t {
uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz) 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) uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
uint8_t use_fast_pwm; // Use fast PWM implementation when oneshot enabled uint8_t use_fast_pwm; // Use fast PWM implementation when oneshot enabled
uint8_t use_oneshot42; // Oneshot42
#ifdef USE_SERVOS #ifdef USE_SERVOS
servoMixer_t customServoMixer[MAX_SERVO_RULES]; servoMixer_t customServoMixer[MAX_SERVO_RULES];

View File

@ -31,8 +31,8 @@
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse); void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse); void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void fastPWMMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse); void fastPWMMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, uint8_t useOneshot42);
void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex); void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t useOneshot42);
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse); void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
/* /*
@ -805,9 +805,9 @@ if (init->useBuzzerP6) {
#endif #endif
if (init->useOneshot) { if (init->useOneshot) {
if (init->useFastPWM) { if (init->useFastPWM) {
fastPWMMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse); fastPWMMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse, init->useOneshot42);
} else { } else {
pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount); pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->useOneshot42);
} }
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ; pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ;
} else if (isMotorBrushed(init->motorPwmRate)) { } else if (isMotorBrushed(init->motorPwmRate)) {

View File

@ -36,10 +36,9 @@
#define MAX_INPUTS 8 #define MAX_INPUTS 8
#define PWM_TIMER_MHZ 1 #define PWM_TIMER_MHZ 1
#define ONESHOT125_TIMER_MHZ 8 #define ONESHOT125_TIMER_MHZ 24
#define PWM_BRUSHED_TIMER_MHZ 8 #define PWM_BRUSHED_TIMER_MHZ 8
typedef struct sonarGPIOConfig_s { typedef struct sonarGPIOConfig_s {
GPIO_TypeDef *gpio; GPIO_TypeDef *gpio;
uint16_t triggerPin; uint16_t triggerPin;
@ -61,6 +60,7 @@ typedef struct drv_pwm_config_s {
bool useVbat; bool useVbat;
bool useOneshot; bool useOneshot;
bool useFastPWM; bool useFastPWM;
bool useOneshot42;
bool useSoftSerial; bool useSoftSerial;
bool useLEDStrip; bool useLEDStrip;
#ifdef SONAR #ifdef SONAR

View File

@ -135,6 +135,16 @@ static void pwmWriteStandard(uint8_t index, uint16_t value)
*motors[index]->ccr = value; *motors[index]->ccr = value;
} }
static void pwmWriteOneshot(uint8_t index, uint16_t value)
{
*motors[index]->ccr = value * 3; // 24Mhz -> 8Mhz
}
static void pwmWriteOneshot42(uint8_t index, uint16_t value)
{
*motors[index]->ccr = value;
}
void pwmWriteMotor(uint8_t index, uint16_t value) void pwmWriteMotor(uint8_t index, uint16_t value)
{ {
if (motors[index] && index < MAX_MOTORS) if (motors[index] && index < MAX_MOTORS)
@ -190,17 +200,25 @@ void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motor
motors[motorIndex]->pwmWritePtr = pwmWriteStandard; motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
} }
void fastPWMMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse) void fastPWMMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, uint8_t useOneshot42)
{ {
uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000; uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, ONESHOT125_TIMER_MHZ, hz / motorPwmRate, idlePulse); motors[motorIndex] = pwmOutConfig(timerHardware, ONESHOT125_TIMER_MHZ, hz / motorPwmRate, idlePulse);
motors[motorIndex]->pwmWritePtr = pwmWriteStandard; if (useOneshot42) {
motors[motorIndex]->pwmWritePtr = pwmWriteOneshot42;
} else {
motors[motorIndex]->pwmWritePtr = pwmWriteOneshot;
}
} }
void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex) void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t useOneshot42)
{ {
motors[motorIndex] = pwmOutConfig(timerHardware, ONESHOT125_TIMER_MHZ, 0xFFFF, 0); motors[motorIndex] = pwmOutConfig(timerHardware, ONESHOT125_TIMER_MHZ, 0xFFFF, 0);
motors[motorIndex]->pwmWritePtr = pwmWriteStandard; if (useOneshot42) {
motors[motorIndex]->pwmWritePtr = pwmWriteOneshot42;
} else {
motors[motorIndex]->pwmWritePtr = pwmWriteOneshot;
}
} }
#ifdef USE_SERVOS #ifdef USE_SERVOS

View File

@ -528,7 +528,8 @@ const clivalue_t valueTable[] = {
{ "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
{ "enable_fast_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_fast_pwm, .config.lookup = { TABLE_OFF_ON } }, { "use_fast_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_fast_pwm, .config.lookup = { TABLE_OFF_ON } },
{ "use_oneshot42", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_oneshot42, .config.lookup = { TABLE_OFF_ON } },
#ifdef CC3D #ifdef CC3D
{ "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } }, { "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } },
#endif #endif

View File

@ -309,6 +309,7 @@ void init(void)
pwm_params.useOneshot = feature(FEATURE_ONESHOT125); pwm_params.useOneshot = feature(FEATURE_ONESHOT125);
pwm_params.useFastPWM = masterConfig.use_fast_pwm ? true : false; pwm_params.useFastPWM = masterConfig.use_fast_pwm ? true : false;
pwm_params.useOneshot42 = masterConfig.use_oneshot42 ? true : false;
pwm_params.motorPwmRate = masterConfig.motor_pwm_rate; pwm_params.motorPwmRate = masterConfig.motor_pwm_rate;
pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand; pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand;
if (feature(FEATURE_3D)) if (feature(FEATURE_3D))