From 6f90ee27a594626f8c9401b8fe2083783796c88c Mon Sep 17 00:00:00 2001 From: Richard Unger Date: Sat, 27 Aug 2022 22:32:43 +0200 Subject: [PATCH] add routines for 1-pwm in driver code --- src/BLDCMotor.cpp | 2 +- src/drivers/hardware_api.h | 22 +++++++++++++++++++ src/drivers/hardware_specific/generic_mcu.cpp | 21 ++++++++++++++++++ 3 files changed, 44 insertions(+), 1 deletion(-) diff --git a/src/BLDCMotor.cpp b/src/BLDCMotor.cpp index 21b43faa..f6b5ef38 100644 --- a/src/BLDCMotor.cpp +++ b/src/BLDCMotor.cpp @@ -345,7 +345,7 @@ void BLDCMotor::move(float new_target) { // when switching to a 2-component representation. if( controller!=MotionControlType::angle_openloop && controller!=MotionControlType::velocity_openloop ) shaft_angle = shaftAngle(); // read value even if motor is disabled to keep the monitoring updated but not in openloop mode - // get angular velocity + // get angular velocity TODO the velocity reading probably also shouldn't happen in open loop modes? shaft_velocity = shaftVelocity(); // read value even if motor is disabled to keep the monitoring updated // if disabled do nothing diff --git a/src/drivers/hardware_api.h b/src/drivers/hardware_api.h index cb2385b7..a1ca885a 100644 --- a/src/drivers/hardware_api.h +++ b/src/drivers/hardware_api.h @@ -19,6 +19,17 @@ typedef struct GenericDriverParams { float dead_zone; } GenericDriverParams; +/** + * Configuring PWM frequency, resolution and alignment + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param pwm_frequency - frequency in hertz - if applicable + * @param pinA pinA pwm pin + * + * @return -1 if failed, or pointer to internal driver parameters struct if successful + */ +void* _configure1PWM(long pwm_frequency, const int pinA); /** * Configuring PWM frequency, resolution and alignment @@ -80,6 +91,17 @@ void* _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const */ void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l); +/** + * Function setting the duty cycle to the pwm pin (ex. analogWrite()) + * - Stepper driver - 2PWM setting + * - hardware specific + * + * @param dc_a duty cycle phase A [0, 1] + * @param dc_b duty cycle phase B [0, 1] + * @param params the driver parameters + */ +void _writeDutyCycle1PWM(float dc_a, void* params); + /** * Function setting the duty cycle to the pwm pin (ex. analogWrite()) * - Stepper driver - 2PWM setting diff --git a/src/drivers/hardware_specific/generic_mcu.cpp b/src/drivers/hardware_specific/generic_mcu.cpp index cb3bfd34..fe6e65a4 100644 --- a/src/drivers/hardware_specific/generic_mcu.cpp +++ b/src/drivers/hardware_specific/generic_mcu.cpp @@ -5,6 +5,18 @@ __attribute__((weak)) void analogWrite(uint8_t pin, int value){ }; #endif +// function setting the high pwm frequency to the supplied pin +// - Stepper motor - 1PWM setting +// - hardware speciffic +// in generic case dont do anything +__attribute__((weak)) void* _configure1PWM(long pwm_frequency, const int pinA) { + GenericDriverParams* params = new GenericDriverParams { + .pins = { pinA }, + .pwm_frequency = pwm_frequency + }; + return params; +} + // function setting the high pwm frequency to the supplied pins // - Stepper motor - 2PWM setting // - hardware speciffic @@ -59,6 +71,15 @@ __attribute__((weak)) void* _configure6PWM(long pwm_frequency, float dead_zone, } +// function setting the pwm duty cycle to the hardware +// - Stepper motor - 1PWM setting +// - hardware speciffic +__attribute__((weak)) void _writeDutyCycle1PWM(float dc_a, void* params){ + // transform duty cycle from [0,1] to [0,255] + analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a); +} + + // function setting the pwm duty cycle to the hardware // - Stepper motor - 2PWM setting // - hardware speciffic