Skip to content

add routines for 1-pwm in driver code #211

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 1 commit into from
Aug 29, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion src/BLDCMotor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
22 changes: 22 additions & 0 deletions src/drivers/hardware_api.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down
21 changes: 21 additions & 0 deletions src/drivers/hardware_specific/generic_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down