#4: PWM $ settings

This commit is contained in:
Todd Fleming 2017-05-13 13:54:50 -04:00
parent 5a862a5e30
commit b1ecb47bec
8 changed files with 52 additions and 25 deletions

View File

@ -1,7 +1,8 @@
![GitHub Logo](https://github.com/gnea/gnea-Media/blob/master/Grbl%20Logo/Grbl%20Logo%20250px.png?raw=true) ![GitHub Logo](https://github.com/gnea/gnea-Media/blob/master/Grbl%20Logo/Grbl%20Logo%20250px.png?raw=true)
*** ***
_Click the `Release` tab to download pre-compiled `.bin` files or just [click here](https://github.com/gnea/grbl-LPC/releases)_ Old releases are in the `Release` tab. See [cprezzi's branch](https://github.com/cprezzi/grbl-LPC) for more recent releases.
Note: cprezzi's branch disables current control and has defaults more suitable for other boards.
*** ***
This is GRBL 1.1 ported to the LPC1769. It can run on Smoothieboard. This is GRBL 1.1 ported to the LPC1769. It can run on Smoothieboard.
@ -10,13 +11,8 @@ Usage notes:
If it doesn't, try installing VCOM_lib/usbser.inf. If it doesn't, try installing VCOM_lib/usbser.inf.
* This doesn't pass the sdcard to the host. Once installed you need to use a micro sdcard adaptor to replace or change it. * This doesn't pass the sdcard to the host. Once installed you need to use a micro sdcard adaptor to replace or change it.
* Only tested with lasers with PWM. Non-PWM spindle control not ported. * Only tested with lasers with PWM. Non-PWM spindle control not ported.
* These are fixed PWM config values. To change these you'll have to change ```SPINDLE_PWM_*``` in config.h and rebuild.
* Pin 2.4
* 40 kHz
* PWM off value: 0%
* Mimimum PWM value: 0%
* Maximum PWM value: 100%
* These are defaults for easy-to-change config values. * These are defaults for easy-to-change config values.
* WPos enabled for LaserWeb compatability ($10=0)
* Laser mode: ON ($32) * Laser mode: ON ($32)
* Minimum S value: 0.0 ($31) * Minimum S value: 0.0 ($31)
* Maximum S value: 1.0 ($30) * Maximum S value: 1.0 ($30)
@ -24,6 +20,10 @@ Usage notes:
* Control inputs not yet ported (e.g. Cycle Start and Safety Door switches) * Control inputs not yet ported (e.g. Cycle Start and Safety Door switches)
New configuration settings New configuration settings
* $33 is PWM frequency in Hz
* $34 is PWM off value in %
* $35 is PWM min value in %
* $36 is PWM max value in %
* $140, $141, $142 are X, Y, Z current (amps) * $140, $141, $142 are X, Y, Z current (amps)
* Default to 0.0 A to avoid burning out your motors * Default to 0.0 A to avoid burning out your motors
* Your motors will likely stall if you don't set these! * Your motors will likely stall if you don't set these!

View File

@ -359,11 +359,6 @@
// pwm = scaled value. settings.rpm_min scales to SPINDLE_PWM_MIN_VALUE. settings.rpm_max // pwm = scaled value. settings.rpm_min scales to SPINDLE_PWM_MIN_VALUE. settings.rpm_max
// scales to SPINDLE_PWM_MAX_VALUE. // scales to SPINDLE_PWM_MAX_VALUE.
#define SPINDLE_PWM_PERIOD (SystemCoreClock / 40000) // SystemCoreClock / frequency
#define SPINDLE_PWM_OFF_VALUE (SPINDLE_PWM_PERIOD * 0.0) // SPINDLE_PWM_PERIOD * fraction
#define SPINDLE_PWM_MIN_VALUE (SPINDLE_PWM_PERIOD * 0.0) // SPINDLE_PWM_PERIOD * fraction
#define SPINDLE_PWM_MAX_VALUE (SPINDLE_PWM_PERIOD * 1.0) // SPINDLE_PWM_PERIOD * fraction
// Used by variable spindle output only. This forces the PWM output to a minimum duty cycle when enabled. // Used by variable spindle output only. This forces the PWM output to a minimum duty cycle when enabled.
// The PWM pin will still read 0V when the spindle is disabled. Most users will not need this option, but // The PWM pin will still read 0V when the spindle is disabled. Most users will not need this option, but
// it may be useful in certain scenarios. This minimum PWM settings coincides with the spindle rpm minimum // it may be useful in certain scenarios. This minimum PWM settings coincides with the spindle rpm minimum
@ -755,13 +750,17 @@
#define DEFAULT_X_MAX_TRAVEL 200.0 // mm #define DEFAULT_X_MAX_TRAVEL 200.0 // mm
#define DEFAULT_Y_MAX_TRAVEL 200.0 // mm #define DEFAULT_Y_MAX_TRAVEL 200.0 // mm
#define DEFAULT_Z_MAX_TRAVEL 200.0 // mm #define DEFAULT_Z_MAX_TRAVEL 200.0 // mm
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
#define DEFAULT_SPINDLE_PWM_OFF_VALUE 0.0 // Percent
#define DEFAULT_SPINDLE_PWM_MIN_VALUE 0.0 // Percent
#define DEFAULT_SPINDLE_PWM_MAX_VALUE 100.0 // Percent
#define DEFAULT_SPINDLE_RPM_MAX 1.0 // rpm #define DEFAULT_SPINDLE_RPM_MAX 1.0 // rpm
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm #define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_STEP_PULSE_MICROSECONDS 1 #define DEFAULT_STEP_PULSE_MICROSECONDS 1
#define DEFAULT_STEPPING_INVERT_MASK 0 #define DEFAULT_STEPPING_INVERT_MASK 0
#define DEFAULT_DIRECTION_INVERT_MASK 0 #define DEFAULT_DIRECTION_INVERT_MASK 0
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled) #define DEFAULT_STEPPER_IDLE_LOCK_TIME 25 // msec (0-254, 255 keeps steppers enabled)
#define DEFAULT_STATUS_REPORT_MASK 1 // MPos enabled #define DEFAULT_STATUS_REPORT_MASK 0 // WPos enabled
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm #define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
#define DEFAULT_ARC_TOLERANCE 0.002 // mm #define DEFAULT_ARC_TOLERANCE 0.002 // mm
#define DEFAULT_REPORT_INCHES 0 // false #define DEFAULT_REPORT_INCHES 0 // false

View File

@ -208,6 +208,10 @@ void report_grbl_settings() {
#else #else
report_util_uint8_setting(32,0); report_util_uint8_setting(32,0);
#endif #endif
report_util_float_setting(33,settings.spindle_pwm_freq,N_DECIMAL_SETTINGVALUE);
report_util_float_setting(34,settings.spindle_pwm_off_value,N_DECIMAL_SETTINGVALUE);
report_util_float_setting(35,settings.spindle_pwm_min_value,N_DECIMAL_SETTINGVALUE);
report_util_float_setting(36,settings.spindle_pwm_max_value,N_DECIMAL_SETTINGVALUE);
// Print axis settings // Print axis settings
uint8_t idx, set_idx; uint8_t idx, set_idx;
uint8_t val = AXIS_SETTINGS_START_VAL; uint8_t val = AXIS_SETTINGS_START_VAL;

View File

@ -86,6 +86,10 @@ void settings_restore(uint8_t restore_flag) {
settings.junction_deviation = DEFAULT_JUNCTION_DEVIATION; settings.junction_deviation = DEFAULT_JUNCTION_DEVIATION;
settings.arc_tolerance = DEFAULT_ARC_TOLERANCE; settings.arc_tolerance = DEFAULT_ARC_TOLERANCE;
settings.spindle_pwm_freq = DEFAULT_SPINDLE_PWM_FREQ;
settings.spindle_pwm_off_value = DEFAULT_SPINDLE_PWM_OFF_VALUE;
settings.spindle_pwm_min_value = DEFAULT_SPINDLE_PWM_MIN_VALUE;
settings.spindle_pwm_max_value = DEFAULT_SPINDLE_PWM_MAX_VALUE;
settings.rpm_max = DEFAULT_SPINDLE_RPM_MAX; settings.rpm_max = DEFAULT_SPINDLE_RPM_MAX;
settings.rpm_min = DEFAULT_SPINDLE_RPM_MIN; settings.rpm_min = DEFAULT_SPINDLE_RPM_MIN;
@ -317,6 +321,10 @@ uint8_t settings_store_global_setting(uint8_t parameter, float value) {
return(STATUS_SETTING_DISABLED); return(STATUS_SETTING_DISABLED);
#endif #endif
break; break;
case 33: settings.spindle_pwm_freq = value; spindle_init(); break; // Re-initialize spindle pwm calibration
case 34: settings.spindle_pwm_off_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
case 35: settings.spindle_pwm_min_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
case 36: settings.spindle_pwm_max_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
default: default:
return(STATUS_INVALID_STATEMENT); return(STATUS_INVALID_STATEMENT);
} }

View File

@ -92,6 +92,10 @@ typedef struct {
float junction_deviation; float junction_deviation;
float arc_tolerance; float arc_tolerance;
float spindle_pwm_freq; // Hz
float spindle_pwm_off_value; // Percent
float spindle_pwm_min_value; // Percent
float spindle_pwm_max_value; // Percent
float rpm_max; float rpm_max;
float rpm_min; float rpm_min;

View File

@ -25,13 +25,21 @@
#ifdef VARIABLE_SPINDLE #ifdef VARIABLE_SPINDLE
static float pwm_gradient; // Precalulated value to speed up rpm to PWM conversions. static float pwm_gradient; // Precalulated value to speed up rpm to PWM conversions.
float spindle_pwm_period;
float spindle_pwm_off_value;
float spindle_pwm_min_value;
float spindle_pwm_max_value;
#endif #endif
void spindle_init() void spindle_init()
{ {
#ifdef VARIABLE_SPINDLE #ifdef VARIABLE_SPINDLE
pwm_init(&SPINDLE_PWM_CHANNEL, SPINDLE_PWM_USE_PRIMARY_PIN, SPINDLE_PWM_USE_SECONDARY_PIN, SPINDLE_PWM_PERIOD, 0); spindle_pwm_period = (SystemCoreClock / settings.spindle_pwm_freq);
spindle_pwm_off_value = (spindle_pwm_period * settings.spindle_pwm_off_value / 100);
spindle_pwm_min_value = (spindle_pwm_period * settings.spindle_pwm_min_value / 100);
spindle_pwm_max_value = (spindle_pwm_period * settings.spindle_pwm_max_value / 100);
pwm_init(&SPINDLE_PWM_CHANNEL, SPINDLE_PWM_USE_PRIMARY_PIN, SPINDLE_PWM_USE_SECONDARY_PIN, spindle_pwm_period, 0);
pwm_enable(&SPINDLE_PWM_CHANNEL); pwm_enable(&SPINDLE_PWM_CHANNEL);
/* not ported /* not ported
@ -44,7 +52,7 @@ void spindle_init()
#endif #endif
*/ */
pwm_gradient = (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)/(settings.rpm_max-settings.rpm_min); pwm_gradient = (spindle_pwm_max_value-spindle_pwm_min_value)/(settings.rpm_max-settings.rpm_min);
#else #else
/* not ported /* not ported
@ -134,21 +142,21 @@ void spindle_stop()
rpm *= (0.010*sys.spindle_speed_ovr); // Scale by spindle speed override value. rpm *= (0.010*sys.spindle_speed_ovr); // Scale by spindle speed override value.
if (rpm <= 0) { if (rpm <= 0) {
sys.spindle_speed = 0; sys.spindle_speed = 0;
pwm_value = SPINDLE_PWM_OFF_VALUE; pwm_value = spindle_pwm_off_value;
} }
else if (rpm <= settings.rpm_min) { else if (rpm <= settings.rpm_min) {
sys.spindle_speed = settings.rpm_min; sys.spindle_speed = settings.rpm_min;
pwm_value = SPINDLE_PWM_MIN_VALUE; pwm_value = spindle_pwm_min_value;
} }
else if (rpm >= settings.rpm_max) { else if (rpm >= settings.rpm_max) {
sys.spindle_speed = settings.rpm_max; sys.spindle_speed = settings.rpm_max;
pwm_value = SPINDLE_PWM_MAX_VALUE - 1; pwm_value = spindle_pwm_max_value - 1;
} }
else { else {
sys.spindle_speed = rpm; sys.spindle_speed = rpm;
pwm_value = floor((rpm - settings.rpm_min) * pwm_gradient) + SPINDLE_PWM_MIN_VALUE; pwm_value = floor((rpm - settings.rpm_min) * pwm_gradient) + spindle_pwm_min_value;
if(pwm_value >= SPINDLE_PWM_MAX_VALUE) if(pwm_value >= spindle_pwm_max_value)
pwm_value = SPINDLE_PWM_MAX_VALUE - 1; pwm_value = spindle_pwm_max_value - 1;
} }
return(pwm_value); return(pwm_value);
} }

View File

@ -40,6 +40,10 @@ uint8_t spindle_get_state();
// Immediately sets spindle running state with direction and spindle rpm via PWM, if enabled. // Immediately sets spindle running state with direction and spindle rpm via PWM, if enabled.
// Called by spindle_sync() after sync and parking motion/spindle stop override during restore. // Called by spindle_sync() after sync and parking motion/spindle stop override during restore.
#ifdef VARIABLE_SPINDLE #ifdef VARIABLE_SPINDLE
extern float spindle_pwm_period;
extern float spindle_pwm_off_value;
extern float spindle_pwm_min_value;
extern float spindle_pwm_max_value;
// Called by g-code parser when setting spindle state and requires a buffer sync. // Called by g-code parser when setting spindle state and requires a buffer sync.
void spindle_sync(uint8_t state, float rpm); void spindle_sync(uint8_t state, float rpm);

View File

@ -385,7 +385,7 @@ extern "C" void TIMER1_IRQHandler()
st_go_idle(); st_go_idle();
#ifdef VARIABLE_SPINDLE #ifdef VARIABLE_SPINDLE
// Ensure pwm is set properly upon completion of rate-controlled motion. // Ensure pwm is set properly upon completion of rate-controlled motion.
if (st.exec_block->is_pwm_rate_adjusted) { spindle_set_speed(SPINDLE_PWM_OFF_VALUE); } if (st.exec_block->is_pwm_rate_adjusted) { spindle_set_speed(spindle_pwm_off_value); }
#endif #endif
system_set_exec_state_flag(EXEC_CYCLE_STOP); // Flag main program for cycle end system_set_exec_state_flag(EXEC_CYCLE_STOP); // Flag main program for cycle end
return; // Nothing to do but exit. return; // Nothing to do but exit.
@ -907,7 +907,7 @@ void st_prep_buffer()
prep.current_spindle_pwm = spindle_compute_pwm_value(rpm); prep.current_spindle_pwm = spindle_compute_pwm_value(rpm);
} else { } else {
sys.spindle_speed = 0.0; sys.spindle_speed = 0.0;
prep.current_spindle_pwm = SPINDLE_PWM_OFF_VALUE; prep.current_spindle_pwm = spindle_pwm_off_value;
} }
bit_false(sys.step_control,STEP_CONTROL_UPDATE_SPINDLE_PWM); bit_false(sys.step_control,STEP_CONTROL_UPDATE_SPINDLE_PWM);
} }