PWM calculation correction.
- The PWM calculation was a little bit off and has been corrected. - Edited the unused settings strings to be smaller and just show what the settings are, rather than include units. May include this in the master build, if it fits. - The minimum spindle PWM define in config.h needed to be update for cpu map compatibilty.
This commit is contained in:
parent
1161056bf2
commit
998f23b9ce
@ -1,3 +1,13 @@
|
||||
----------------
|
||||
Date: 2016-11-04
|
||||
Author: Sonny Jeon
|
||||
Subject: Fixed a g-code parser issue caused by last commit.
|
||||
|
||||
- G-code parser refactoring in the last commit wasn’t tested. Found and
|
||||
fixed issues with G28.1/30.1 and G38.x probe commands. They were not
|
||||
being accepted due to a borked mantissa check.
|
||||
|
||||
|
||||
----------------
|
||||
Date: 2016-11-04
|
||||
Author: Sonny Jeon
|
||||
|
@ -363,7 +363,7 @@
|
||||
// in mind that you will begin to lose PWM resolution with increased minimum PWM values, since you have less
|
||||
// and less range over the total 256 PWM levels to signal different spindle speeds.
|
||||
// NOTE: Compute duty cycle at the minimum PWM by this equation: (% duty cycle)=(SPINDLE_MINIMUM_PWM/256)*100
|
||||
// #define SPINDLE_MINIMUM_PWM 5 // Default disabled. Uncomment to enable. Must be greater than zero. Integer (1-255).
|
||||
// #define SPINDLE_MINIMUM_PWM_VALUE 5 // Default disabled. Uncomment to enable. Must be greater than zero. Integer (1-255).
|
||||
|
||||
// By default on a 328p(Uno), Grbl combines the variable spindle PWM and the enable into one pin to help
|
||||
// preserve I/O pins. For certain setups, these may need to be separate pins. This configure option uses
|
||||
|
@ -23,7 +23,7 @@
|
||||
|
||||
// Grbl versioning system
|
||||
#define GRBL_VERSION "1.1d"
|
||||
#define GRBL_VERSION_BUILD "20161104"
|
||||
#define GRBL_VERSION_BUILD "20161112"
|
||||
|
||||
// Define standard libraries used by Grbl.
|
||||
#include <avr/io.h>
|
||||
|
@ -49,45 +49,43 @@ static void report_util_setting_string(uint8_t n) {
|
||||
serial_write(' ');
|
||||
serial_write('(');
|
||||
switch(n) {
|
||||
case 0: printPgmString(PSTR("stp pulse:us")); break;
|
||||
case 1: printPgmString(PSTR("idl delay:ms")); break;
|
||||
case 2: printPgmString(PSTR("stp inv:msk")); break;
|
||||
case 3: printPgmString(PSTR("dir inv:msk")); break;
|
||||
case 4: printPgmString(PSTR("stp enbl inv")); break;
|
||||
case 0: printPgmString(PSTR("stp pulse")); break;
|
||||
case 1: printPgmString(PSTR("idl delay")); break;
|
||||
case 2: printPgmString(PSTR("stp inv")); break;
|
||||
case 3: printPgmString(PSTR("dir inv")); break;
|
||||
case 4: printPgmString(PSTR("stp en inv")); break;
|
||||
case 5: printPgmString(PSTR("lim inv")); break;
|
||||
case 6: printPgmString(PSTR("prb inv")); break;
|
||||
case 10: printPgmString(PSTR("rpt:msk")); break;
|
||||
case 11: printPgmString(PSTR("jnc dev:mm")); break;
|
||||
case 12: printPgmString(PSTR("arc tol:mm")); break;
|
||||
case 10: printPgmString(PSTR("rpt")); break;
|
||||
case 11: printPgmString(PSTR("jnc dev")); break;
|
||||
case 12: printPgmString(PSTR("arc tol")); break;
|
||||
case 13: printPgmString(PSTR("rpt inch")); break;
|
||||
case 20: printPgmString(PSTR("sft lim")); break;
|
||||
case 21: printPgmString(PSTR("hrd lim")); break;
|
||||
case 22: printPgmString(PSTR("hm cyc")); break;
|
||||
case 23: printPgmString(PSTR("hm dir inv:msk")); break;
|
||||
case 24: printPgmString(PSTR("hm feed:mm/min")); break;
|
||||
case 25: printPgmString(PSTR("hm seek:mm/min")); break;
|
||||
case 26: printPgmString(PSTR("hm delay:ms")); break;
|
||||
case 27: printPgmString(PSTR("hm off:mm")); break;
|
||||
case 23: printPgmString(PSTR("hm dir inv")); break;
|
||||
case 24: printPgmString(PSTR("hm feed")); break;
|
||||
case 25: printPgmString(PSTR("hm seek")); break;
|
||||
case 26: printPgmString(PSTR("hm delay")); break;
|
||||
case 27: printPgmString(PSTR("hm pulloff")); break;
|
||||
case 30: printPgmString(PSTR("rpm max")); break;
|
||||
case 31: printPgmString(PSTR("rpm min")); break;
|
||||
case 32: printPgmString(PSTR("laser")); break;
|
||||
default:
|
||||
n -= AXIS_SETTINGS_START_VAL;
|
||||
uint8_t idx = 0;
|
||||
while (n < 10) {
|
||||
if (n<10) {
|
||||
print_uint8_base10(n+idx);
|
||||
while (n >= AXIS_SETTINGS_INCREMENT) {
|
||||
n -= AXIS_SETTINGS_INCREMENT;
|
||||
idx++;
|
||||
}
|
||||
serial_write(n+'x');
|
||||
switch (idx) {
|
||||
case 0: printPgmString(PSTR(":stp/mm")); break;
|
||||
case 1: printPgmString(PSTR(":mm/min")); break;
|
||||
case 2: printPgmString(PSTR(":mm/s^2")); break;
|
||||
case 3: printPgmString(PSTR(":mm max")); break;
|
||||
}
|
||||
} else {
|
||||
n -= 10;
|
||||
idx++;
|
||||
}
|
||||
}
|
||||
break;
|
||||
}
|
||||
report_util_comment_line_feed();
|
||||
}
|
||||
@ -97,14 +95,12 @@ static void report_util_setting_string(uint8_t n) {
|
||||
static void report_util_uint8_setting(uint8_t n, int val) {
|
||||
report_util_setting_prefix(n);
|
||||
print_uint8_base10(val);
|
||||
report_util_line_feed();
|
||||
// report_util_setting_string(n);
|
||||
report_util_line_feed(); // report_util_setting_string(n);
|
||||
}
|
||||
static void report_util_float_setting(uint8_t n, float val, uint8_t n_decimal) {
|
||||
report_util_setting_prefix(n);
|
||||
printFloat(val,n_decimal);
|
||||
report_util_line_feed();
|
||||
// report_util_setting_string(n);
|
||||
report_util_line_feed(); // report_util_setting_string(n);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -136,7 +136,7 @@ void spindle_stop()
|
||||
uint8_t spindle_compute_pwm_value(float rpm) // 328p PWM register is 8-bit.
|
||||
{
|
||||
uint8_t pwm_value;
|
||||
rpm *= (0.01*sys.spindle_speed_ovr); // Scale by spindle speed override value.
|
||||
rpm *= (0.010*sys.spindle_speed_ovr); // Scale by spindle speed override value.
|
||||
// Calculate PWM register value based on rpm max/min settings and programmed rpm.
|
||||
if ((settings.rpm_min >= settings.rpm_max) || (rpm >= settings.rpm_max)) {
|
||||
// No PWM range possible. Set simple on/off spindle control pin state.
|
||||
@ -154,7 +154,7 @@ void spindle_stop()
|
||||
// Compute intermediate PWM value with linear spindle speed model.
|
||||
// NOTE: A nonlinear model could be installed here, if required, but keep it VERY light-weight.
|
||||
sys.spindle_speed = rpm;
|
||||
pwm_value = floor( (rpm-settings.rpm_min)*pwm_gradient + (SPINDLE_PWM_MIN_VALUE+0.5) );
|
||||
pwm_value = floor((rpm-settings.rpm_min)*pwm_gradient) + SPINDLE_PWM_MIN_VALUE;
|
||||
}
|
||||
return(pwm_value);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user