Compare commits
4 Commits
beta04-v1.
...
beta05-cor
Author | SHA1 | Date | |
---|---|---|---|
17121a2652 | |||
b48c3c7c51 | |||
0471485259 | |||
063b1f6748 |
14
README.md
14
README.md
@ -1,7 +1,7 @@
|
||||

|
||||
|
||||
***
|
||||
_Click the `Release` tab to download pre-compiled `.bin` files or just [click here](https://github.com/gnea/grbl-LPC/releases)_
|
||||
_Click the `Release` tab to download pre-compiled `.bin` files or just [click here](https://github.com/cprezzi/grbl-LPC/releases)_
|
||||
***
|
||||
This is GRBL 1.1 ported to the LPC1769. It can run on Smoothieboard.
|
||||
|
||||
@ -10,20 +10,22 @@ Usage notes:
|
||||
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.
|
||||
* 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
|
||||
* This special version supports setting PWM frequency by $33. Default is 5000 Hz. Pin can only be changes in config.h.
|
||||
* Pin 2.5
|
||||
* 5 kHz
|
||||
* PWM off value: 0%
|
||||
* Mimimum PWM value: 0%
|
||||
* Maximum PWM value: 100%
|
||||
* These are defaults for easy-to-change config values.
|
||||
* Laser mode: ON ($32)
|
||||
* Maximum S value: 1000.0 ($30)
|
||||
* Minimum S value: 0.0 ($31)
|
||||
* Maximum S value: 1.0 ($30)
|
||||
* Laser mode: 1 ($32)
|
||||
* Laser PWM frequency: 5000 ($33)
|
||||
* Hard limits not yet ported
|
||||
* Control inputs not yet ported (e.g. Cycle Start and Safety Door switches)
|
||||
|
||||
New configuration settings
|
||||
* $33 is PWM frequency in Hz
|
||||
* $140, $141, $142 are X, Y, Z current (amps)
|
||||
* Default to 0.0 A to avoid burning out your motors
|
||||
* Your motors will likely stall if you don't set these!
|
||||
|
@ -103,12 +103,12 @@
|
||||
// on separate pin, but homed in one cycle. Also, it should be noted that the function of hard limits
|
||||
// will not be affected by pin sharing.
|
||||
// NOTE: Defaults are set for a traditional 3-axis CNC machine. Z-axis first to clear, followed by X & Y.
|
||||
#define HOMING_CYCLE_0 (1<<Z_AXIS) // REQUIRED: First move Z to clear workspace.
|
||||
#define HOMING_CYCLE_1 ((1<<X_AXIS)|(1<<Y_AXIS)) // OPTIONAL: Then move X,Y at the same time.
|
||||
//#define HOMING_CYCLE_0 (1<<Z_AXIS) // REQUIRED: First move Z to clear workspace.
|
||||
//#define HOMING_CYCLE_1 ((1<<X_AXIS)|(1<<Y_AXIS)) // OPTIONAL: Then move X,Y at the same time.
|
||||
// #define HOMING_CYCLE_2 // OPTIONAL: Uncomment and add axes mask to enable
|
||||
|
||||
// NOTE: The following are two examples to setup homing for 2-axis machines.
|
||||
// #define HOMING_CYCLE_0 ((1<<X_AXIS)|(1<<Y_AXIS)) // NOT COMPATIBLE WITH COREXY: Homes both X-Y in one cycle.
|
||||
#define HOMING_CYCLE_0 ((1<<X_AXIS)|(1<<Y_AXIS)) // NOT COMPATIBLE WITH COREXY: Homes both X-Y in one cycle.
|
||||
|
||||
// #define HOMING_CYCLE_0 (1<<X_AXIS) // COREXY COMPATIBLE: First home X
|
||||
// #define HOMING_CYCLE_1 (1<<Y_AXIS) // COREXY COMPATIBLE: Then home Y
|
||||
@ -359,10 +359,10 @@
|
||||
// pwm = scaled value. settings.rpm_min scales to SPINDLE_PWM_MIN_VALUE. settings.rpm_max
|
||||
// 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
|
||||
//#define SPINDLE_PWM_PERIOD (SystemCoreClock / 40000) // SystemCoreClock / frequency
|
||||
#define SPINDLE_PWM_OFF_VALUE 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.
|
||||
// The PWM pin will still read 0V when the spindle is disabled. Most users will not need this option, but
|
||||
@ -663,10 +663,10 @@
|
||||
#define LIMIT_DDR LPC_GPIO1->FIODIR
|
||||
#define LIMIT_PIN LPC_GPIO1->FIOPIN
|
||||
#define LIMIT_PORT LPC_GPIO1->FIOPIN
|
||||
#define X_LIMIT_BIT 25 // X-MIN=24, X-MAX=25
|
||||
#define X_LIMIT_BIT 24 // X-MIN=24, X-MAX=25
|
||||
#define Y_LIMIT_BIT 27 // Y-MIN=26, Y-MAX=27
|
||||
#define Z_LIMIT_BIT 29 // Z-MIN=28, Z-MAX=29
|
||||
#define LIMIT_MASK ((1<<X_LIMIT_BIT)|(1<<Y_LIMIT_BIT)|(1<<Z_LIMIT_BIT)) // All limit bits
|
||||
#define LIMIT_MASK ((1<<X_LIMIT_BIT)|(1<<Y_LIMIT_BIT)) //|(1<<Z_LIMIT_BIT)) // All limit bits
|
||||
// hard limits not ported #define LIMIT_INT PCIE0 // Pin change interrupt enable pin
|
||||
// hard limits not ported #define LIMIT_INT_vect PCINT0_vect
|
||||
// hard limits not ported #define LIMIT_PCMSK PCMSK0 // Pin change interrupt register
|
||||
@ -728,53 +728,54 @@
|
||||
// PWM Channel PWM1_CH1 PWM1_CH2 PWM1_CH3 PWM1_CH4 PWM1_CH5 PWM1_CH6
|
||||
// Primary pin P1.18 P1.20 P1.21 P1.23 P1.24 P1.26
|
||||
// Secondary pin P2.0 P2.1 P2.2 P2.3 P2.4 P2.5
|
||||
#define SPINDLE_PWM_CHANNEL PWM1_CH5
|
||||
#define SPINDLE_PWM_CHANNEL PWM1_CH6
|
||||
#define SPINDLE_PWM_USE_PRIMARY_PIN false
|
||||
#define SPINDLE_PWM_USE_SECONDARY_PIN true
|
||||
|
||||
// Stepper current control
|
||||
#define CURRENT_I2C Driver_I2C1 // I2C driver for current control. Comment out to disable.
|
||||
//#define CURRENT_I2C Driver_I2C1 // I2C driver for current control. Comment out to disable.
|
||||
#define CURRENT_MCP44XX_ADDR 0b0101100 // Address of MCP44XX
|
||||
#define CURRENT_WIPERS {0, 1, 6, 7}; // Wiper registers (X, Y, Z, A)
|
||||
#define CURRENT_FACTOR 113.33 // Convert amps to digipot value
|
||||
|
||||
// Paste default settings definitions here.
|
||||
#define DEFAULT_X_STEPS_PER_MM 158.0
|
||||
#define DEFAULT_Y_STEPS_PER_MM 158.0
|
||||
#define DEFAULT_Z_STEPS_PER_MM 158.0
|
||||
#define DEFAULT_X_MAX_RATE 30000 // mm/min
|
||||
#define DEFAULT_Y_MAX_RATE 30000 // mm/min
|
||||
#define DEFAULT_Z_MAX_RATE 500.0 // mm/min
|
||||
#define DEFAULT_X_ACCELERATION (5000.0*60*60) // 5000*60*60 mm/min^2 = 5000 mm/sec^2
|
||||
#define DEFAULT_Y_ACCELERATION (5000.0*60*60) // 5000*60*60 mm/min^2 = 5000 mm/sec^2
|
||||
#define DEFAULT_Z_ACCELERATION (5000.0*60*60) // 5000*60*60 mm/min^2 = 5000 mm/sec^2
|
||||
#define DEFAULT_X_STEPS_PER_MM 160.0
|
||||
#define DEFAULT_Y_STEPS_PER_MM 160.0
|
||||
#define DEFAULT_Z_STEPS_PER_MM 160.0
|
||||
#define DEFAULT_X_MAX_RATE 24000 // mm/min
|
||||
#define DEFAULT_Y_MAX_RATE 24000 // mm/min
|
||||
#define DEFAULT_Z_MAX_RATE 24000 // mm/min
|
||||
#define DEFAULT_X_ACCELERATION (2500.0*60*60) // 5000*60*60 mm/min^2 = 5000 mm/sec^2
|
||||
#define DEFAULT_Y_ACCELERATION (2500.0*60*60) // 5000*60*60 mm/min^2 = 5000 mm/sec^2
|
||||
#define DEFAULT_Z_ACCELERATION (2500.0*60*60) // 5000*60*60 mm/min^2 = 5000 mm/sec^2
|
||||
#define DEFAULT_X_CURRENT 0.0 // amps
|
||||
#define DEFAULT_Y_CURRENT 0.0 // amps
|
||||
#define DEFAULT_Z_CURRENT 0.0 // amps
|
||||
#define DEFAULT_A_CURRENT 0.0 // amps
|
||||
#define DEFAULT_X_MAX_TRAVEL 200.0 // mm
|
||||
#define DEFAULT_X_MAX_TRAVEL 300.0 // mm
|
||||
#define DEFAULT_Y_MAX_TRAVEL 200.0 // mm
|
||||
#define DEFAULT_Z_MAX_TRAVEL 200.0 // mm
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1.0 // rpm
|
||||
#define DEFAULT_Z_MAX_TRAVEL 50.0 // mm
|
||||
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
|
||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 1
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
||||
#define DEFAULT_STEPPING_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_STATUS_REPORT_MASK 1 // MPos enabled
|
||||
#define DEFAULT_STATUS_REPORT_MASK 0 // WPos enabled
|
||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||
#define DEFAULT_REPORT_INCHES 0 // false
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // false
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 0 // false
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // false
|
||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // false
|
||||
#define DEFAULT_LASER_MODE 1 // true
|
||||
#define DEFAULT_HOMING_ENABLE 0 // false
|
||||
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
||||
#define DEFAULT_HOMING_FEED_RATE 25.0 // mm/min
|
||||
#define DEFAULT_HOMING_SEEK_RATE 500.0 // mm/min
|
||||
#define DEFAULT_HOMING_FEED_RATE 50.0 // mm/min
|
||||
#define DEFAULT_HOMING_SEEK_RATE 6000.0 // mm/min
|
||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
|
||||
|
||||
|
@ -41,6 +41,7 @@
|
||||
#define DEFAULT_X_MAX_TRAVEL 200.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Y_MAX_TRAVEL 200.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Z_MAX_TRAVEL 200.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
|
||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
||||
@ -65,6 +66,49 @@
|
||||
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
|
||||
#endif
|
||||
|
||||
#ifdef DEFAULTS_K40
|
||||
// Description: K40 Lasercutter (typical chinese 40W CO2 laser cutter/engraver)
|
||||
#define DEFAULT_X_STEPS_PER_MM 160.0
|
||||
#define DEFAULT_Y_STEPS_PER_MM 160.0
|
||||
#define DEFAULT_Z_STEPS_PER_MM 160.0
|
||||
#define DEFAULT_X_MAX_RATE 24000.0 // mm/min
|
||||
#define DEFAULT_Y_MAX_RATE 24000.0 // mm/min
|
||||
#define DEFAULT_Z_MAX_RATE 24000.0 // mm/min
|
||||
#define DEFAULT_X_ACCELERATION (2500.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Y_ACCELERATION (2500.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_Z_ACCELERATION (2500.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
|
||||
#define DEFAULT_X_CURRENT 0.0 // amps
|
||||
#define DEFAULT_Y_CURRENT 0.0 // amps
|
||||
#define DEFAULT_Z_CURRENT 0.0 // amps
|
||||
#define DEFAULT_A_CURRENT 0.0 // amps
|
||||
#define DEFAULT_X_MAX_TRAVEL 300.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Y_MAX_TRAVEL 200.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_Z_MAX_TRAVEL 50.0 // mm NOTE: Must be a positive value.
|
||||
#define DEFAULT_SPINDLE_PWM_FREQ 5000 // Hz
|
||||
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
|
||||
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS 10
|
||||
#define DEFAULT_STEPPING_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_STATUS_REPORT_MASK 0 // WPos enabled
|
||||
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
|
||||
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
|
||||
#define DEFAULT_REPORT_INCHES 0 // false
|
||||
#define DEFAULT_INVERT_ST_ENABLE 0 // false
|
||||
#define DEFAULT_INVERT_LIMIT_PINS 1 // false
|
||||
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
|
||||
#define DEFAULT_INVERT_PROBE_PIN 0 // false
|
||||
#define DEFAULT_LASER_MODE 1 // false
|
||||
#define DEFAULT_HOMING_ENABLE 0 // false
|
||||
#define DEFAULT_HOMING_DIR_MASK 0 // move positive dir
|
||||
#define DEFAULT_HOMING_FEED_RATE 50.0 // mm/min
|
||||
#define DEFAULT_HOMING_SEEK_RATE 6000.0 // mm/min
|
||||
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
|
||||
#define DEFAULT_HOMING_PULLOFF 1.0 // mm
|
||||
#endif
|
||||
|
||||
#ifdef DEFAULTS_SHERLINE_5400
|
||||
// Description: Sherline 5400 mill with three NEMA 23 Keling KL23H256-21-8B 185 oz-in stepper motors,
|
||||
// driven by three Pololu A4988 stepper drivers with a 30V, 6A power supply at 1.5A per winding.
|
||||
|
@ -71,6 +71,7 @@ static void report_util_setting_string(uint8_t n) {
|
||||
case 30: printPgmString(PSTR("rpm max")); break;
|
||||
case 31: printPgmString(PSTR("rpm min")); break;
|
||||
case 32: printPgmString(PSTR("laser")); break;
|
||||
case 33: printPgmString(PSTR("spindle_pwm_freq")); break;
|
||||
default:
|
||||
n -= AXIS_SETTINGS_START_VAL;
|
||||
uint8_t idx = 0;
|
||||
@ -96,6 +97,11 @@ static void report_util_uint8_setting(uint8_t n, int val) {
|
||||
print_uint8_base10(val);
|
||||
report_util_line_feed(); // report_util_setting_string(n);
|
||||
}
|
||||
static void report_util_uint32_setting(uint8_t n, int val) {
|
||||
report_util_setting_prefix(n);
|
||||
print_uint32_base10(val);
|
||||
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);
|
||||
@ -208,6 +214,7 @@ void report_grbl_settings() {
|
||||
#else
|
||||
report_util_uint8_setting(32,0);
|
||||
#endif
|
||||
report_util_uint32_setting(33,settings.spindle_pwm_freq);
|
||||
// Print axis settings
|
||||
uint8_t idx, set_idx;
|
||||
uint8_t val = AXIS_SETTINGS_START_VAL;
|
||||
|
@ -86,6 +86,7 @@ void settings_restore(uint8_t restore_flag) {
|
||||
settings.junction_deviation = DEFAULT_JUNCTION_DEVIATION;
|
||||
settings.arc_tolerance = DEFAULT_ARC_TOLERANCE;
|
||||
|
||||
settings.spindle_pwm_freq = DEFAULT_SPINDLE_PWM_FREQ;
|
||||
settings.rpm_max = DEFAULT_SPINDLE_RPM_MAX;
|
||||
settings.rpm_min = DEFAULT_SPINDLE_RPM_MIN;
|
||||
|
||||
@ -317,6 +318,7 @@ uint8_t settings_store_global_setting(uint8_t parameter, float value) {
|
||||
return(STATUS_SETTING_DISABLED);
|
||||
#endif
|
||||
break;
|
||||
case 33: settings.spindle_pwm_freq = value; spindle_init(); break; // Re-initialize spindle pwm calibration
|
||||
default:
|
||||
return(STATUS_INVALID_STATEMENT);
|
||||
}
|
||||
|
@ -92,6 +92,7 @@ typedef struct {
|
||||
float junction_deviation;
|
||||
float arc_tolerance;
|
||||
|
||||
uint16_t spindle_pwm_freq;
|
||||
float rpm_max;
|
||||
float rpm_min;
|
||||
|
||||
|
@ -25,13 +25,23 @@
|
||||
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
static float pwm_gradient; // Precalulated value to speed up rpm to PWM conversions.
|
||||
static float spindle_pwm_period;
|
||||
static float spindle_pwm_off_value;
|
||||
static float spindle_pwm_min_value;
|
||||
static float spindle_pwm_max_value;
|
||||
#endif
|
||||
|
||||
|
||||
void spindle_init()
|
||||
{
|
||||
#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 * 0.0); // SPINDLE_PWM_PERIOD * fraction
|
||||
spindle_pwm_min_value = (spindle_pwm_period * 0.0); // SPINDLE_PWM_PERIOD * fraction
|
||||
spindle_pwm_max_value = (spindle_pwm_period * 1.0); // SPINDLE_PWM_PERIOD * fraction
|
||||
|
||||
//pwm_init(&SPINDLE_PWM_CHANNEL, SPINDLE_PWM_USE_PRIMARY_PIN, SPINDLE_PWM_USE_SECONDARY_PIN, SPINDLE_PWM_PERIOD, 0);
|
||||
pwm_init(&SPINDLE_PWM_CHANNEL, SPINDLE_PWM_USE_PRIMARY_PIN, SPINDLE_PWM_USE_SECONDARY_PIN, spindle_pwm_period, 0); //SPINDLE_PWM_PERIOD
|
||||
pwm_enable(&SPINDLE_PWM_CHANNEL);
|
||||
|
||||
/* not ported
|
||||
@ -44,7 +54,8 @@ void spindle_init()
|
||||
#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);
|
||||
pwm_gradient = (spindle_pwm_max_value-spindle_pwm_min_value)/(settings.rpm_max-settings.rpm_min);
|
||||
|
||||
#else
|
||||
/* not ported
|
||||
@ -134,21 +145,21 @@ void spindle_stop()
|
||||
rpm *= (0.010*sys.spindle_speed_ovr); // Scale by spindle speed override value.
|
||||
if (rpm <= 0) {
|
||||
sys.spindle_speed = 0;
|
||||
pwm_value = SPINDLE_PWM_OFF_VALUE;
|
||||
pwm_value = spindle_pwm_off_value; //SPINDLE_PWM_OFF_VALUE
|
||||
}
|
||||
else if (rpm <= settings.rpm_min) {
|
||||
sys.spindle_speed = settings.rpm_min;
|
||||
pwm_value = SPINDLE_PWM_MIN_VALUE;
|
||||
pwm_value = spindle_pwm_min_value; //SPINDLE_PWM_MIN_VALUE
|
||||
}
|
||||
else if (rpm >= settings.rpm_max) {
|
||||
sys.spindle_speed = settings.rpm_max;
|
||||
pwm_value = SPINDLE_PWM_MAX_VALUE - 1;
|
||||
pwm_value = spindle_pwm_max_value - 1; //SPINDLE_PWM_MAX_VALUE
|
||||
}
|
||||
else {
|
||||
sys.spindle_speed = rpm;
|
||||
pwm_value = floor((rpm - settings.rpm_min) * pwm_gradient) + SPINDLE_PWM_MIN_VALUE;
|
||||
if(pwm_value >= SPINDLE_PWM_MAX_VALUE)
|
||||
pwm_value = SPINDLE_PWM_MAX_VALUE - 1;
|
||||
pwm_value = floor((rpm - settings.rpm_min) * pwm_gradient) + spindle_pwm_min_value; //SPINDLE_PWM_MIN_VALUE
|
||||
if(pwm_value >= spindle_pwm_max_value) //SPINDLE_PWM_MAX_VALUE
|
||||
pwm_value = spindle_pwm_max_value - 1; //SPINDLE_PWM_MAX_VALUE
|
||||
}
|
||||
return(pwm_value);
|
||||
}
|
||||
|
Reference in New Issue
Block a user