mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-02 19:02:35 +02:00
Removing test prefs stuff and adding BESCSpindle class
This commit is contained in:
@@ -59,7 +59,6 @@ void setup() {
|
|||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Using machine:%s", MACHINE_STRING);
|
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Using machine:%s", MACHINE_STRING);
|
||||||
#endif
|
#endif
|
||||||
settings_init(); // Load Grbl settings from EEPROM
|
settings_init(); // Load Grbl settings from EEPROM
|
||||||
grbl_preferences.begin(GRBL_PREFERENCES_NAMESPACE, true); // readonly = false
|
|
||||||
stepper_init(); // Configure stepper pins and interrupt timers
|
stepper_init(); // Configure stepper pins and interrupt timers
|
||||||
system_ini(); // Configure pinout pins and pin-change interrupt (Renamed due to conflict with esp32 files)
|
system_ini(); // Configure pinout pins and pin-change interrupt (Renamed due to conflict with esp32 files)
|
||||||
memset(sys_position, 0, sizeof(sys_position)); // Clear machine position.
|
memset(sys_position, 0, sizeof(sys_position)); // Clear machine position.
|
||||||
@@ -99,11 +98,9 @@ void setup() {
|
|||||||
bt_config.begin();
|
bt_config.begin();
|
||||||
#endif
|
#endif
|
||||||
inputBuffer.begin();
|
inputBuffer.begin();
|
||||||
grbl_preferences.end(); // everyone should have their prefs by now
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop() {
|
void loop() {
|
||||||
grbl_preferences.begin(GRBL_PREFERENCES_NAMESPACE, true); // readonly = false
|
|
||||||
// Reset system variables.
|
// Reset system variables.
|
||||||
uint8_t prior_state = sys.state;
|
uint8_t prior_state = sys.state;
|
||||||
memset(&sys, 0, sizeof(system_t)); // Clear system struct variable.
|
memset(&sys, 0, sizeof(system_t)); // Clear system struct variable.
|
||||||
@@ -120,7 +117,7 @@ void loop() {
|
|||||||
// Reset Grbl primary systems.
|
// Reset Grbl primary systems.
|
||||||
serial_reset_read_buffer(CLIENT_ALL); // Clear serial read buffer
|
serial_reset_read_buffer(CLIENT_ALL); // Clear serial read buffer
|
||||||
gc_init(); // Set g-code parser to default state
|
gc_init(); // Set g-code parser to default state
|
||||||
spindle_select(settings.spindle_type);
|
spindle_select(SPINDLE_TYPE);
|
||||||
coolant_init();
|
coolant_init();
|
||||||
limits_init();
|
limits_init();
|
||||||
probe_init();
|
probe_init();
|
||||||
@@ -132,6 +129,5 @@ void loop() {
|
|||||||
// put your main code here, to run repeatedly:
|
// put your main code here, to run repeatedly:
|
||||||
report_init_message(CLIENT_ALL);
|
report_init_message(CLIENT_ALL);
|
||||||
// Start Grbl main loop. Processes program inputs and executes them.
|
// Start Grbl main loop. Processes program inputs and executes them.
|
||||||
grbl_preferences.end(); // everyone should have their prefs by now
|
|
||||||
protocol_main_loop();
|
protocol_main_loop();
|
||||||
}
|
}
|
||||||
|
@@ -52,4 +52,4 @@
|
|||||||
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // labeled Hold, needs external pullup
|
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // labeled Hold, needs external pullup
|
||||||
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // labeled Start, needs external pullup
|
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // labeled Start, needs external pullup
|
||||||
|
|
||||||
#define DEFAULT_SPINDLE_TYPE SPINDLE_TYPE_PWM
|
#define SPINDLE_TYPE SPINDLE_TYPE_BESC
|
||||||
|
@@ -43,10 +43,10 @@
|
|||||||
#define SPINDLE_PWM_PIN GPIO_NUM_25
|
#define SPINDLE_PWM_PIN GPIO_NUM_25
|
||||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_22
|
#define SPINDLE_ENABLE_PIN GPIO_NUM_22
|
||||||
|
|
||||||
#define HUANYANG_TXD_PIN GPIO_NUM_17
|
#define SPINDLE_TYPE SPINDLE_TYPE_HUANYANG
|
||||||
#define HUANYANG_RXD_PIN GPIO_NUM_4
|
#define HUANYANG_TXD_PIN GPIO_NUM_17
|
||||||
#define HUANYANG_RTS_PIN GPIO_NUM_16
|
#define HUANYANG_RXD_PIN GPIO_NUM_4
|
||||||
|
#define HUANYANG_RTS_PIN GPIO_NUM_16
|
||||||
|
|
||||||
#define X_LIMIT_PIN GPIO_NUM_34
|
#define X_LIMIT_PIN GPIO_NUM_34
|
||||||
#define Y_LIMIT_PIN GPIO_NUM_35
|
#define Y_LIMIT_PIN GPIO_NUM_35
|
||||||
|
@@ -143,14 +143,6 @@
|
|||||||
#define DEFAULT_SPINDLE_MAX_VALUE 100.0 // $36 Percent (extended set)
|
#define DEFAULT_SPINDLE_MAX_VALUE 100.0 // $36 Percent (extended set)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef DEFAULT_SPINDLE_PWM_BIT_PRECISION // $37
|
|
||||||
#define DEFAULT_SPINDLE_PWM_BIT_PRECISION 8
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef DEFAULT_SPINDLE_TYPE // $38
|
|
||||||
#define DEFAULT_SPINDLE_TYPE SPINDLE_TYPE_PWM
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// ================ user settings =====================
|
// ================ user settings =====================
|
||||||
#ifndef DEFAULT_USER_INT_80
|
#ifndef DEFAULT_USER_INT_80
|
||||||
#define DEFAULT_USER_INT_80 0 // $80 User integer setting
|
#define DEFAULT_USER_INT_80 0 // $80 User integer setting
|
||||||
|
@@ -39,7 +39,6 @@
|
|||||||
|
|
||||||
#include "defaults.h"
|
#include "defaults.h"
|
||||||
#include "settings.h"
|
#include "settings.h"
|
||||||
#include "grbl_preferences.h"
|
|
||||||
#include "system.h"
|
#include "system.h"
|
||||||
|
|
||||||
#include "planner.h"
|
#include "planner.h"
|
||||||
|
@@ -1,44 +0,0 @@
|
|||||||
#include "grbl.h"
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
Preferences grbl_preferences;
|
|
||||||
|
|
||||||
void grbl_preferences_init() {
|
|
||||||
grbl_preferences.begin(GRBL_PREFERENCES_NAMESPACE, false); // readonly = false
|
|
||||||
spindle_read_prefs(grbl_preferences); //
|
|
||||||
grbl_preferences.end();
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
bool grbl_prefs_change(const char* line, int* cmd, String& cmd_params) {
|
|
||||||
String buffer = line;
|
|
||||||
String key = "";
|
|
||||||
String value = "";
|
|
||||||
|
|
||||||
// grbl_preferences.begin(GRBL_PREFERENCES_NAMESPACE, false); // readonly = false
|
|
||||||
|
|
||||||
// TODO probably need more error checking
|
|
||||||
int close_bracket = buffer.indexOf("]", 2); // find the closing bracket
|
|
||||||
if (close_bracket > -1) {
|
|
||||||
key = buffer.substring(2, close_bracket);
|
|
||||||
if (close_bracket < buffer.length()) {
|
|
||||||
value = buffer.substring(close_bracket + 1);
|
|
||||||
} else {
|
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "no value found");
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
switch (buffer[2]) {
|
|
||||||
case 'S':
|
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Hey spindle please set key:%s to value:%s", key.c_str(), value.c_str());
|
|
||||||
return true;
|
|
||||||
break;
|
|
||||||
default:
|
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Unknown setting prefix %c", buffer[2]);
|
|
||||||
}
|
|
||||||
// grbl_preferences.end();
|
|
||||||
|
|
||||||
return false;
|
|
||||||
}
|
|
@@ -1,14 +0,0 @@
|
|||||||
|
|
||||||
#ifndef GRBL_PREFERENCES_H
|
|
||||||
#define GRBL_PREFERENCES_H
|
|
||||||
|
|
||||||
#define GRBL_PREFERENCES_NAMESPACE "Grbl_ESP32"
|
|
||||||
|
|
||||||
#include "grbl.h"
|
|
||||||
|
|
||||||
extern Preferences grbl_preferences;
|
|
||||||
|
|
||||||
void grbl_preferences_init();
|
|
||||||
bool grbl_prefs_change(const char* line, int* cmd, String& cmd_params);
|
|
||||||
|
|
||||||
#endif
|
|
@@ -8,7 +8,7 @@
|
|||||||
|
|
||||||
// !!! For initial testing, start with test_drive.h which disables
|
// !!! For initial testing, start with test_drive.h which disables
|
||||||
// all I/O pins
|
// all I/O pins
|
||||||
#include "Machines/4axis_external_driver.h"
|
#include "Machines/3axis_v4.h"
|
||||||
|
|
||||||
// !!! For actual use, change the line above to select a board
|
// !!! For actual use, change the line above to select a board
|
||||||
// from Machines/, for example:
|
// from Machines/, for example:
|
||||||
|
@@ -1,13 +1,15 @@
|
|||||||
#ifndef _machine_common_h
|
#ifndef _machine_common_h
|
||||||
#define _machine_common_h
|
#define _machine_common_h
|
||||||
|
|
||||||
/*
|
#ifndef SPINDLE_TYPE
|
||||||
|
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifndef SPINDLE_PWM_BIT_PRECISION
|
#ifndef SPINDLE_PWM_BIT_PRECISION
|
||||||
#define SPINDLE_PWM_BIT_PRECISION 8
|
#define SPINDLE_PWM_BIT_PRECISION 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define SPINDLE_PWM_MAX_VALUE ((1<<SPINDLE_PWM_BIT_PRECISION) - 1)
|
#define SPINDLE_PWM_MAX_VALUE ((1<<SPINDLE_PWM_BIT_PRECISION) - 1)
|
||||||
*/
|
|
||||||
|
|
||||||
// Grbl setting that are common to all machines
|
// Grbl setting that are common to all machines
|
||||||
// It should not be necessary to change anything herein
|
// It should not be necessary to change anything herein
|
||||||
|
@@ -118,18 +118,11 @@ void protocol_main_loop() {
|
|||||||
} else if (line[0] == '[') {
|
} else if (line[0] == '[') {
|
||||||
int cmd = 0;
|
int cmd = 0;
|
||||||
String cmd_params;
|
String cmd_params;
|
||||||
if (line[1] == '$') { // it is a Grbl preference
|
if (COMMANDS::check_command(line, &cmd, cmd_params)) {
|
||||||
if (!grbl_prefs_change(line, &cmd, cmd_params)){
|
ESPResponseStream espresponse(client, true);
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Unknow Command...%s", line);
|
if (!COMMANDS::execute_internal_command(cmd, cmd_params, LEVEL_GUEST, &espresponse))
|
||||||
}
|
report_status_message(STATUS_GCODE_UNSUPPORTED_COMMAND, CLIENT_ALL);
|
||||||
} else { // it might be a [ESP...] comamnd
|
} else grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Unknow Command...%s", line);
|
||||||
if (COMMANDS::check_command(line, &cmd, cmd_params)) {
|
|
||||||
ESPResponseStream espresponse(client, true);
|
|
||||||
if (!COMMANDS::execute_internal_command(cmd, cmd_params, LEVEL_GUEST, &espresponse))
|
|
||||||
report_status_message(STATUS_GCODE_UNSUPPORTED_COMMAND, CLIENT_ALL);
|
|
||||||
} else
|
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Unknow Command...%s", line);
|
|
||||||
}
|
|
||||||
} else if (sys.state & (STATE_ALARM | STATE_JOG)) {
|
} else if (sys.state & (STATE_ALARM | STATE_JOG)) {
|
||||||
// Everything else is gcode. Block if in alarm or jog mode.
|
// Everything else is gcode. Block if in alarm or jog mode.
|
||||||
report_status_message(STATUS_SYSTEM_GC_LOCK, client);
|
report_status_message(STATUS_SYSTEM_GC_LOCK, client);
|
||||||
|
@@ -314,9 +314,7 @@ void report_grbl_settings(uint8_t client, uint8_t show_extended) {
|
|||||||
sprintf(setting, "$33=%5.3f\r\n", settings.spindle_pwm_freq); strcat(rpt, setting);
|
sprintf(setting, "$33=%5.3f\r\n", settings.spindle_pwm_freq); strcat(rpt, setting);
|
||||||
sprintf(setting, "$34=%3.3f\r\n", settings.spindle_pwm_off_value); strcat(rpt, setting);
|
sprintf(setting, "$34=%3.3f\r\n", settings.spindle_pwm_off_value); strcat(rpt, setting);
|
||||||
sprintf(setting, "$35=%3.3f\r\n", settings.spindle_pwm_min_value); strcat(rpt, setting);
|
sprintf(setting, "$35=%3.3f\r\n", settings.spindle_pwm_min_value); strcat(rpt, setting);
|
||||||
sprintf(setting, "$36=%3.3f\r\n", settings.spindle_pwm_max_value); strcat(rpt, setting);
|
sprintf(setting, "$36=%3.3f\r\n", settings.spindle_pwm_max_value); strcat(rpt, setting);
|
||||||
sprintf(setting, "$37=%d\r\n", settings.spindle_pwm_precision_bits); strcat(rpt, setting);
|
|
||||||
sprintf(setting, "$38=%d\r\n", settings.spindle_type); strcat(rpt, setting);
|
|
||||||
for (uint8_t index = 0; index < USER_SETTING_COUNT; index++) {
|
for (uint8_t index = 0; index < USER_SETTING_COUNT; index++) {
|
||||||
sprintf(setting, "$%d=%d\r\n", 80 + index, settings.machine_int16[index]); strcat(rpt, setting);
|
sprintf(setting, "$%d=%d\r\n", 80 + index, settings.machine_int16[index]); strcat(rpt, setting);
|
||||||
}
|
}
|
||||||
|
@@ -71,8 +71,6 @@ void settings_restore(uint8_t restore_flag) {
|
|||||||
settings.spindle_pwm_off_value = DEFAULT_SPINDLE_OFF_VALUE; // $34 Percent (extended set)
|
settings.spindle_pwm_off_value = DEFAULT_SPINDLE_OFF_VALUE; // $34 Percent (extended set)
|
||||||
settings.spindle_pwm_min_value = DEFAULT_SPINDLE_MIN_VALUE; // $35 Percent (extended set)
|
settings.spindle_pwm_min_value = DEFAULT_SPINDLE_MIN_VALUE; // $35 Percent (extended set)
|
||||||
settings.spindle_pwm_max_value = DEFAULT_SPINDLE_MAX_VALUE; // $36 Percent (extended set)
|
settings.spindle_pwm_max_value = DEFAULT_SPINDLE_MAX_VALUE; // $36 Percent (extended set)
|
||||||
settings.spindle_pwm_precision_bits = MIN(8, DEFAULT_SPINDLE_PWM_BIT_PRECISION); // $37
|
|
||||||
settings.spindle_type= DEFAULT_SPINDLE_TYPE; // $38
|
|
||||||
|
|
||||||
settings.homing_dir_mask = DEFAULT_HOMING_DIR_MASK;
|
settings.homing_dir_mask = DEFAULT_HOMING_DIR_MASK;
|
||||||
settings.homing_feed_rate = DEFAULT_HOMING_FEED_RATE;
|
settings.homing_feed_rate = DEFAULT_HOMING_FEED_RATE;
|
||||||
@@ -379,12 +377,10 @@ uint8_t settings_store_global_setting(uint8_t parameter, float value) {
|
|||||||
settings.flags &= ~BITFLAG_LASER_MODE;
|
settings.flags &= ~BITFLAG_LASER_MODE;
|
||||||
my_spindle->init(); // update the spindle class
|
my_spindle->init(); // update the spindle class
|
||||||
break;
|
break;
|
||||||
case 33: settings.spindle_pwm_freq = value; spindle_select(settings.spindle_type); break; // Re-initialize spindle pwm calibration
|
case 33: settings.spindle_pwm_freq = value; spindle_select(SPINDLE_TYPE); break; // Re-initialize spindle pwm calibration
|
||||||
case 34: settings.spindle_pwm_off_value = value; spindle_select(settings.spindle_type); break; // Re-initialize spindle pwm calibration
|
case 34: settings.spindle_pwm_off_value = value; spindle_select(SPINDLE_TYPE); break; // Re-initialize spindle pwm calibration
|
||||||
case 35: settings.spindle_pwm_min_value = value; spindle_select(settings.spindle_type); break; // Re-initialize spindle pwm calibration
|
case 35: settings.spindle_pwm_min_value = value; spindle_select(SPINDLE_TYPE); break; // Re-initialize spindle pwm calibration
|
||||||
case 36: settings.spindle_pwm_max_value = value; spindle_select(settings.spindle_type); break; // Re-initialize spindle pwm calibration
|
case 36: settings.spindle_pwm_max_value = value; spindle_select(SPINDLE_TYPE); break; // Re-initialize spindle pwm calibration
|
||||||
case 37: settings.spindle_pwm_precision_bits = MIN(8, value);spindle_select(settings.spindle_type); break;
|
|
||||||
case 38: settings.spindle_type = value; spindle_select(settings.spindle_type); break;
|
|
||||||
case 80:
|
case 80:
|
||||||
case 81:
|
case 81:
|
||||||
case 82:
|
case 82:
|
||||||
|
@@ -107,8 +107,6 @@ typedef struct {
|
|||||||
float spindle_pwm_off_value; // $34 Percent (extended set)
|
float spindle_pwm_off_value; // $34 Percent (extended set)
|
||||||
float spindle_pwm_min_value; // $35 Percent (extended set)
|
float spindle_pwm_min_value; // $35 Percent (extended set)
|
||||||
float spindle_pwm_max_value; // $36 Percent (extended set)
|
float spindle_pwm_max_value; // $36 Percent (extended set)
|
||||||
uint8_t spindle_pwm_precision_bits; // $37 PWM pwm precision in bits (extended set)
|
|
||||||
uint8_t spindle_type; // $38 The spindle class to be used (extended set)
|
|
||||||
|
|
||||||
float rpm_max;
|
float rpm_max;
|
||||||
float rpm_min;
|
float rpm_min;
|
||||||
|
97
Grbl_Esp32/tools/BESCSpindle.cpp
Normal file
97
Grbl_Esp32/tools/BESCSpindle.cpp
Normal file
@@ -0,0 +1,97 @@
|
|||||||
|
/*
|
||||||
|
Important ESC Settings
|
||||||
|
$33=50 // Hz this is the typical good frequency for an ESC
|
||||||
|
#define DEFAULT_SPINDLE_FREQ 5000.0 // $33 Hz (extended set)
|
||||||
|
|
||||||
|
Determine the typical min and max pulse length of your ESC
|
||||||
|
min_pulse is typically 1ms (0.001 sec) or less
|
||||||
|
max_pulse is typically 2ms (0.002 sec) or more
|
||||||
|
|
||||||
|
determine PWM_period. It is (1/freq) if freq = 50...period = 0.02
|
||||||
|
|
||||||
|
determine pulse length for min_pulse and max_pulse in percent.
|
||||||
|
|
||||||
|
(pulse / PWM_period)
|
||||||
|
min_pulse = (0.001 / 0.02) = 0.05 = 5% so ... $34 and $35 = 5.0
|
||||||
|
max_pulse = (0.002 / .02) = 0.1 = 10% so ... $36=10
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "grbl.h"
|
||||||
|
#include "SpindleClass.h"
|
||||||
|
|
||||||
|
|
||||||
|
// don't change these
|
||||||
|
#define BESC_PWM_FREQ 50.0 // Hz
|
||||||
|
#define BESC_PWM_BIT_PRECISION 16 // bits
|
||||||
|
#define BESC_DEFAULT_MIN_PULSE 5.0 // percent
|
||||||
|
#define BESC_DEFAULT_MAX_PULSE 10.0 // percent
|
||||||
|
|
||||||
|
|
||||||
|
void BESCSpindle :: init() {
|
||||||
|
|
||||||
|
get_pin_numbers();
|
||||||
|
|
||||||
|
if (_output_pin == UNDEFINED_PIN) {
|
||||||
|
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning: BESC output pin not defined");
|
||||||
|
return; // We cannot continue without the output pin
|
||||||
|
}
|
||||||
|
|
||||||
|
// override some settings to what is required for a BESC
|
||||||
|
_pwm_freq = BESC_PWM_FREQ;
|
||||||
|
_pwm_precision = 16;
|
||||||
|
|
||||||
|
// to do make these tweakable using existing setting as percentages on these defaults
|
||||||
|
_pwm_off_value = BESC_DEFAULT_MIN_PULSE;
|
||||||
|
_pwm_min_value = BESC_DEFAULT_MIN_PULSE;
|
||||||
|
_pwm_max_value = BESC_DEFAULT_MAX_PULSE;
|
||||||
|
|
||||||
|
ledcSetup(_spindle_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
|
||||||
|
ledcAttachPin(_output_pin, _spindle_pwm_chan_num); // attach the PWM to the pin
|
||||||
|
|
||||||
|
if (_enable_pin != UNDEFINED_PIN)
|
||||||
|
pinMode(_enable_pin, OUTPUT);
|
||||||
|
|
||||||
|
config_message();
|
||||||
|
}
|
||||||
|
|
||||||
|
// prints the startup message of the spindle config
|
||||||
|
void BESCSpindle :: config_message() {
|
||||||
|
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "BESC spindle on GPIO %d", _output_pin);
|
||||||
|
}
|
||||||
|
|
||||||
|
float BESCSpindle::set_rpm(float rpm) {
|
||||||
|
uint32_t pwm_value;
|
||||||
|
|
||||||
|
if (_output_pin == UNDEFINED_PIN)
|
||||||
|
return rpm;
|
||||||
|
|
||||||
|
// apply speed overrides
|
||||||
|
rpm *= (0.010 * sys.spindle_speed_ovr); // Scale by spindle speed override value (percent)
|
||||||
|
|
||||||
|
// apply limits limits
|
||||||
|
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm)) {
|
||||||
|
rpm = _max_rpm;
|
||||||
|
} else if (rpm != 0.0 && rpm <= _min_rpm) {
|
||||||
|
rpm = _min_rpm;
|
||||||
|
}
|
||||||
|
|
||||||
|
sys.spindle_speed = rpm;
|
||||||
|
|
||||||
|
// determine the pwm value
|
||||||
|
if (rpm == 0.0) {
|
||||||
|
pwm_value = _pwm_off_value;
|
||||||
|
} else if (rpm == _min_rpm) {
|
||||||
|
pwm_value = _pwm_min_value;
|
||||||
|
} else if (rpm == _max_rpm) {
|
||||||
|
pwm_value = _pwm_max_value;
|
||||||
|
} else {
|
||||||
|
pwm_value = floor((rpm - _min_rpm) * _pwm_gradient) + _pwm_min_value;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
|
||||||
|
set_enable_pin(rpm != 0);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
set_pwm(pwm_value);
|
||||||
|
return rpm;
|
||||||
|
}
|
@@ -195,6 +195,9 @@ bool HuanyangSpindle :: get_response(uint16_t length) {
|
|||||||
0x01 0x05 0x02 0x09 0xC4 0xBF 0x0F Write Frequency (0x9C4 = 2500 = 25.00HZ)
|
0x01 0x05 0x02 0x09 0xC4 0xBF 0x0F Write Frequency (0x9C4 = 2500 = 25.00HZ)
|
||||||
*/
|
*/
|
||||||
float HuanyangSpindle :: set_rpm(float rpm) {
|
float HuanyangSpindle :: set_rpm(float rpm) {
|
||||||
|
|
||||||
|
// TODO add in all the speed modifiers, like override and linearization
|
||||||
|
|
||||||
char msg[7] = {HUANYANG_ADDR, 0x05, 0x02, 0x00, 0x00, 0x00, 0x00};
|
char msg[7] = {HUANYANG_ADDR, 0x05, 0x02, 0x00, 0x00, 0x00, 0x00};
|
||||||
|
|
||||||
// add data (rpm) bytes
|
// add data (rpm) bytes
|
||||||
|
@@ -37,6 +37,6 @@ void Laser :: config_message() {
|
|||||||
"Laser spindle on GPIO:%d, Freq:%.2fHz, Res:%dbits Laser mode:$32=%d",
|
"Laser spindle on GPIO:%d, Freq:%.2fHz, Res:%dbits Laser mode:$32=%d",
|
||||||
_output_pin,
|
_output_pin,
|
||||||
_pwm_freq,
|
_pwm_freq,
|
||||||
settings.spindle_pwm_precision_bits,
|
SPINDLE_PWM_BIT_PRECISION,
|
||||||
isRateAdjusted()); // the current mode
|
isRateAdjusted()); // the current mode
|
||||||
}
|
}
|
@@ -17,7 +17,7 @@
|
|||||||
GNU General Public License for more details.
|
GNU General Public License for more details.
|
||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
*/
|
*/
|
||||||
#include "grbl.h"
|
#include "grbl.h"
|
||||||
#include "SpindleClass.h"
|
#include "SpindleClass.h"
|
||||||
@@ -28,46 +28,19 @@ void PWMSpindle::init() {
|
|||||||
get_pin_numbers();
|
get_pin_numbers();
|
||||||
|
|
||||||
if (_output_pin == UNDEFINED_PIN) {
|
if (_output_pin == UNDEFINED_PIN) {
|
||||||
|
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning: Spindle output pin not defined");
|
||||||
return; // We cannot continue without the output pin
|
return; // We cannot continue without the output pin
|
||||||
}
|
}
|
||||||
|
|
||||||
_min_rpm = grbl_preferences.getFloat("SPIN_MAX_RPM", DEFAULT_SPINDLE_MIN_VALUE);
|
|
||||||
|
|
||||||
_pwm_freq = settings.spindle_pwm_freq;
|
ledcSetup(_spindle_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
|
||||||
_pwm_period = ((1 << settings.spindle_pwm_precision_bits) - 1);
|
ledcAttachPin(_output_pin, _spindle_pwm_chan_num); // attach the PWM to the pin
|
||||||
|
|
||||||
if (settings.spindle_pwm_min_value > settings.spindle_pwm_min_value)
|
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning: Spindle min pwm is greater than max. Check $35 and $36");
|
|
||||||
|
|
||||||
if ((F_TIMERS / _pwm_freq) < _pwm_period)
|
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning spindle PWM precision (%d bits) too high for frequency (%.2f Hz)", settings.spindle_pwm_precision_bits, _pwm_freq);
|
|
||||||
|
|
||||||
// pre-caculate some PWM count values
|
|
||||||
_pwm_off_value = (_pwm_period * settings.spindle_pwm_off_value / 100.0);
|
|
||||||
_pwm_min_value = (_pwm_period * settings.spindle_pwm_min_value / 100.0);
|
|
||||||
_pwm_max_value = (_pwm_period * settings.spindle_pwm_max_value / 100.0);
|
|
||||||
|
|
||||||
#ifdef ENABLE_PIECEWISE_LINEAR_SPINDLE
|
|
||||||
_min_rpm = RPM_MIN;
|
|
||||||
_max_rpm = RPM_MAX;
|
|
||||||
#else
|
|
||||||
_min_rpm = settings.rpm_min;
|
|
||||||
_max_rpm = settings.rpm_max;
|
|
||||||
#endif
|
|
||||||
// The pwm_gradient is the pwm duty cycle units per rpm
|
|
||||||
_pwm_gradient = (_pwm_max_value - _pwm_min_value) / (_max_rpm - _min_rpm);
|
|
||||||
|
|
||||||
_spindle_pwm_chan_num = sys_get_next_PWM_chan_num();
|
|
||||||
ledcSetup(_spindle_pwm_chan_num, (double)_pwm_freq, settings.spindle_pwm_precision_bits); // setup the channel
|
|
||||||
ledcAttachPin(_output_pin, _spindle_pwm_chan_num); // attach the PWM to the pin
|
|
||||||
|
|
||||||
if (_enable_pin != UNDEFINED_PIN)
|
if (_enable_pin != UNDEFINED_PIN)
|
||||||
pinMode(_enable_pin, OUTPUT);
|
pinMode(_enable_pin, OUTPUT);
|
||||||
|
|
||||||
if (_direction_pin != UNDEFINED_PIN)
|
if (_direction_pin != UNDEFINED_PIN)
|
||||||
pinMode(_direction_pin, OUTPUT);
|
pinMode(_direction_pin, OUTPUT);
|
||||||
|
|
||||||
is_reversable = (_direction_pin != UNDEFINED_PIN);
|
|
||||||
|
|
||||||
config_message();
|
config_message();
|
||||||
}
|
}
|
||||||
@@ -93,23 +66,47 @@ void PWMSpindle :: get_pin_numbers() {
|
|||||||
#else
|
#else
|
||||||
_direction_pin = UNDEFINED_PIN;
|
_direction_pin = UNDEFINED_PIN;
|
||||||
#endif
|
#endif
|
||||||
|
is_reversable = (_direction_pin != UNDEFINED_PIN);
|
||||||
|
|
||||||
if (_output_pin == UNDEFINED_PIN)
|
_pwm_freq = settings.spindle_pwm_freq;
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning: Spindle output pin not defined");
|
_pwm_precision = SPINDLE_PWM_BIT_PRECISION;
|
||||||
|
_pwm_period = ((1 << _pwm_precision) - 1);
|
||||||
|
|
||||||
|
|
||||||
|
if (settings.spindle_pwm_min_value > settings.spindle_pwm_min_value)
|
||||||
|
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning: Spindle min pwm is greater than max. Check $35 and $36");
|
||||||
|
|
||||||
|
if ((F_TIMERS / _pwm_freq) < _pwm_period)
|
||||||
|
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning spindle PWM precision (%d bits) too high for frequency (%.2f Hz)", _pwm_precision, _pwm_freq);
|
||||||
|
|
||||||
|
// pre-caculate some PWM count values
|
||||||
|
_pwm_off_value = (_pwm_period * settings.spindle_pwm_off_value / 100.0);
|
||||||
|
_pwm_min_value = (_pwm_period * settings.spindle_pwm_min_value / 100.0);
|
||||||
|
_pwm_max_value = (_pwm_period * settings.spindle_pwm_max_value / 100.0);
|
||||||
|
|
||||||
|
#ifdef ENABLE_PIECEWISE_LINEAR_SPINDLE
|
||||||
|
_min_rpm = RPM_MIN;
|
||||||
|
_max_rpm = RPM_MAX;
|
||||||
|
#else
|
||||||
|
_min_rpm = settings.rpm_min;
|
||||||
|
_max_rpm = settings.rpm_max;
|
||||||
|
#endif
|
||||||
|
// The pwm_gradient is the pwm duty cycle units per rpm
|
||||||
|
_pwm_gradient = (_pwm_max_value - _pwm_min_value) / (_max_rpm - _min_rpm);
|
||||||
|
|
||||||
|
_spindle_pwm_chan_num = sys_get_next_PWM_chan_num();
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
float PWMSpindle::set_rpm(float rpm) {
|
float PWMSpindle::set_rpm(float rpm) {
|
||||||
if (_output_pin == UNDEFINED_PIN)
|
if (_output_pin == UNDEFINED_PIN)
|
||||||
return rpm;
|
return rpm;
|
||||||
|
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Spindle RPM:%5.2f Min:%5.2f Max:%5.2f", rpm, _min_rpm, _max_rpm);
|
|
||||||
|
|
||||||
uint32_t pwm_value;
|
uint32_t pwm_value;
|
||||||
|
|
||||||
// apply overrides and limits
|
// apply overrides and limits
|
||||||
rpm *= (0.010 * sys.spindle_speed_ovr); // Scale by spindle speed override value (percent)
|
rpm *= (0.010 * sys.spindle_speed_ovr); // Scale by spindle speed override value (percent)
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Spindle RPM 1:%5.2f", rpm);
|
|
||||||
|
|
||||||
// Calculate PWM register value based on rpm max/min settings and programmed rpm.
|
// Calculate PWM register value based on rpm max/min settings and programmed rpm.
|
||||||
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm)) {
|
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm)) {
|
||||||
@@ -188,7 +185,7 @@ void PWMSpindle::stop() {
|
|||||||
|
|
||||||
// prints the startup message of the spindle config
|
// prints the startup message of the spindle config
|
||||||
void PWMSpindle :: config_message() {
|
void PWMSpindle :: config_message() {
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "PWM spindle on GPIO %d, freq %.2fHz, Res %d bits", _output_pin, _pwm_freq, settings.spindle_pwm_precision_bits);
|
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "PWM spindle on GPIO %d, freq %.2fHz, Res %d bits", _output_pin, _pwm_freq, _pwm_precision);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@@ -26,7 +26,7 @@
|
|||||||
TODO
|
TODO
|
||||||
Consider breaking into one file per class.
|
Consider breaking into one file per class.
|
||||||
|
|
||||||
Get rid of dependance on machine definition #defines
|
Get rid of dependance on machine definition #defines
|
||||||
SPINDLE_PWM_PIN
|
SPINDLE_PWM_PIN
|
||||||
SPINDLE_ENABLE_PIN
|
SPINDLE_ENABLE_PIN
|
||||||
SPINDLE_DIR_PIN
|
SPINDLE_DIR_PIN
|
||||||
@@ -40,6 +40,7 @@
|
|||||||
#include "RelaySpindle.cpp"
|
#include "RelaySpindle.cpp"
|
||||||
#include "Laser.cpp"
|
#include "Laser.cpp"
|
||||||
#include "HuanyangSpindle.cpp"
|
#include "HuanyangSpindle.cpp"
|
||||||
|
#include "BESCSpindle.cpp"
|
||||||
|
|
||||||
NullSpindle null_spindle;
|
NullSpindle null_spindle;
|
||||||
PWMSpindle pwm_spindle;
|
PWMSpindle pwm_spindle;
|
||||||
@@ -47,11 +48,12 @@ RelaySpindle relay_spindle;
|
|||||||
Laser laser;
|
Laser laser;
|
||||||
DacSpindle dac_spindle;
|
DacSpindle dac_spindle;
|
||||||
HuanyangSpindle huanyang_spindle;
|
HuanyangSpindle huanyang_spindle;
|
||||||
|
BESCSpindle besc_spindle;
|
||||||
|
|
||||||
void spindle_select(uint8_t spindle_type) {
|
void spindle_select(uint8_t spindle_type) {
|
||||||
|
|
||||||
switch (spindle_type) {
|
switch (spindle_type) {
|
||||||
case SPINDLE_TYPE_PWM:
|
case SPINDLE_TYPE_PWM:
|
||||||
my_spindle = &pwm_spindle;
|
my_spindle = &pwm_spindle;
|
||||||
break;
|
break;
|
||||||
case SPINDLE_TYPE_RELAY:
|
case SPINDLE_TYPE_RELAY:
|
||||||
@@ -64,7 +66,10 @@ void spindle_select(uint8_t spindle_type) {
|
|||||||
my_spindle = &dac_spindle;
|
my_spindle = &dac_spindle;
|
||||||
break;
|
break;
|
||||||
case SPINDLE_TYPE_HUANYANG:
|
case SPINDLE_TYPE_HUANYANG:
|
||||||
my_spindle = &huanyang_spindle;
|
my_spindle = &huanyang_spindle;
|
||||||
|
break;
|
||||||
|
case SPINDLE_TYPE_BESC:
|
||||||
|
my_spindle = &besc_spindle;
|
||||||
break;
|
break;
|
||||||
case SPINDLE_TYPE_NONE:
|
case SPINDLE_TYPE_NONE:
|
||||||
default:
|
default:
|
||||||
@@ -74,7 +79,7 @@ void spindle_select(uint8_t spindle_type) {
|
|||||||
my_spindle->init();
|
my_spindle->init();
|
||||||
}
|
}
|
||||||
|
|
||||||
void spindle_read_prefs(Preferences &prefs) {
|
void spindle_read_prefs(Preferences& prefs) {
|
||||||
uint8_t foo = prefs.getUChar("SPIN_TYPE", SPINDLE_TYPE_PWM);
|
uint8_t foo = prefs.getUChar("SPIN_TYPE", SPINDLE_TYPE_PWM);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@@ -33,16 +33,8 @@
|
|||||||
#define SPINDLE_TYPE_LASER 3
|
#define SPINDLE_TYPE_LASER 3
|
||||||
#define SPINDLE_TYPE_DAC 4
|
#define SPINDLE_TYPE_DAC 4
|
||||||
#define SPINDLE_TYPE_HUANYANG 5
|
#define SPINDLE_TYPE_HUANYANG 5
|
||||||
/*
|
#define SPINDLE_TYPE_BESC 6
|
||||||
typedef enum {
|
|
||||||
SPINDLE_TYPE_NONE = 0,
|
|
||||||
SPINDLE_TYPE_PWM,
|
|
||||||
SPINDLE_TYPE_RELAY,
|
|
||||||
SPINDLE_TYPE_LASER,
|
|
||||||
SPINDLE_TYPE_DAC,
|
|
||||||
SPINDLE_TYPE_HUANGYANG,
|
|
||||||
} spindle_type_t;
|
|
||||||
*/
|
|
||||||
#ifndef SPINDLE_CLASS_H
|
#ifndef SPINDLE_CLASS_H
|
||||||
#define SPINDLE_CLASS_H
|
#define SPINDLE_CLASS_H
|
||||||
|
|
||||||
@@ -90,10 +82,8 @@ class PWMSpindle : public Spindle {
|
|||||||
void config_message();
|
void config_message();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
int8_t _spindle_pwm_chan_num;
|
|
||||||
int32_t _current_pwm_duty;
|
int32_t _current_pwm_duty;
|
||||||
float _pwm_gradient; // Precalulated value to speed up rpm to PWM conversions.
|
|
||||||
|
|
||||||
void set_spindle_dir_pin(bool Clockwise);
|
void set_spindle_dir_pin(bool Clockwise);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
@@ -105,8 +95,11 @@ class PWMSpindle : public Spindle {
|
|||||||
uint8_t _output_pin;
|
uint8_t _output_pin;
|
||||||
uint8_t _enable_pin;
|
uint8_t _enable_pin;
|
||||||
uint8_t _direction_pin;
|
uint8_t _direction_pin;
|
||||||
|
int8_t _spindle_pwm_chan_num;
|
||||||
float _pwm_freq;
|
float _pwm_freq;
|
||||||
uint32_t _pwm_period; // how many counts in 1 period
|
uint32_t _pwm_period; // how many counts in 1 period
|
||||||
|
uint8_t _pwm_precision;
|
||||||
|
float _pwm_gradient; // Precalulated value to speed up rpm to PWM conversions.
|
||||||
|
|
||||||
virtual void set_pwm(uint32_t duty);
|
virtual void set_pwm(uint32_t duty);
|
||||||
void set_enable_pin(bool enable_pin);
|
void set_enable_pin(bool enable_pin);
|
||||||
@@ -149,7 +142,7 @@ class HuanyangSpindle : public Spindle {
|
|||||||
virtual void set_state(uint8_t state, float rpm);
|
virtual void set_state(uint8_t state, float rpm);
|
||||||
uint8_t get_state();
|
uint8_t get_state();
|
||||||
float set_rpm(float rpm);
|
float set_rpm(float rpm);
|
||||||
void stop();
|
void stop();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
bool get_response(uint16_t length);
|
bool get_response(uint16_t length);
|
||||||
@@ -164,6 +157,13 @@ class HuanyangSpindle : public Spindle {
|
|||||||
uint8_t _state;
|
uint8_t _state;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
class BESCSpindle : public PWMSpindle {
|
||||||
|
public:
|
||||||
|
void init();
|
||||||
|
void config_message();
|
||||||
|
float set_rpm(float rpm);
|
||||||
|
};
|
||||||
|
|
||||||
extern Spindle* my_spindle;
|
extern Spindle* my_spindle;
|
||||||
|
|
||||||
extern NullSpindle null_spindle;
|
extern NullSpindle null_spindle;
|
||||||
@@ -172,6 +172,7 @@ extern RelaySpindle relay_spindle;
|
|||||||
extern Laser laser;
|
extern Laser laser;
|
||||||
extern DacSpindle dac_spindle;
|
extern DacSpindle dac_spindle;
|
||||||
extern HuanyangSpindle huanyang_spindle;
|
extern HuanyangSpindle huanyang_spindle;
|
||||||
|
extern BESCSpindle besc_spindle;
|
||||||
|
|
||||||
void spindle_select(uint8_t spindle_type);
|
void spindle_select(uint8_t spindle_type);
|
||||||
void spindle_read_prefs(Preferences& prefs);
|
void spindle_read_prefs(Preferences& prefs);
|
||||||
|
Reference in New Issue
Block a user