Merge pull request #83 from saifullah-N/v.1.2.1

V.1.2.1
This commit is contained in:
Sathish Kumar
2023-02-06 14:47:14 +08:00
committed by GitHub
8 changed files with 657 additions and 643 deletions

1
scripts/gplan-init-dev-img.sh Executable file → Normal file
View File

@@ -4,6 +4,7 @@ export LC_ALL=C
cd /mnt/host
# Update the system
apt -o "Acquire::https::Verify-Peer=false" update
# Install packages
apt -o "Acquire::https::Verify-Peer=false" install -y scons build-essential libssl-dev python3-dev

View File

@@ -33,20 +33,19 @@
#include "config.h"
#include "command.h"
#include "exec.h"
#include "estop.h"
#include "util.h"
#include "state.h"
#include <math.h>
typedef struct {
typedef struct
{
float dist;
float speed;
} sync_speed_t;
static struct {
static struct
{
spindle_type_t type;
float override;
sync_speed_t sync_speed;
@@ -64,118 +63,152 @@ static struct {
} spindle = {
.type = SPINDLE_TYPE_DISABLED,
.override = 1,
.sync_speed = {-1, 0}
};
.sync_speed = {-1, 0}};
static float _get_power() {
switch (spindle.type) {
case SPINDLE_TYPE_DISABLED: return 0;
case SPINDLE_TYPE_PWM: return pwm_get();
case SPINDLE_TYPE_HUANYANG: return huanyang_get();
default: return vfd_spindle_get();
static float _get_power()
{
switch (spindle.type)
{
case SPINDLE_TYPE_DISABLED:
return 0;
case SPINDLE_TYPE_PWM:
return pwm_get();
case SPINDLE_TYPE_HUANYANG:
return huanyang_get();
default:
return vfd_spindle_get();
}
}
static float _speed_to_power(float speed) {
static float _speed_to_power(float speed)
{
bool negative = speed < 0;
float power = fabs(speed * spindle.override);
if (power < spindle.min_rpm) power = 0;
else if (spindle.max_rpm <= power) power = 1;
else power *= spindle.inv_max_rpm;
if (power < spindle.min_rpm)
power = 0;
else if (spindle.max_rpm <= power)
power = 1;
else
power *= spindle.inv_max_rpm;
return (negative ^ spindle.reversed) ? -power : power;
}
static void _set_speed(float speed) {
static void _set_speed(float speed)
{
spindle.speed = speed;
float power = _speed_to_power(speed);
if (estop_triggered()) power = 0;
switch (spindle.type)
{
case SPINDLE_TYPE_DISABLED:
break;
switch (spindle.type) {
case SPINDLE_TYPE_DISABLED: break;
case SPINDLE_TYPE_PWM: {
case SPINDLE_TYPE_PWM:
{
// PWM speed updates must be synchronized with stepper movement
spindle.sync_speed.dist = 0;
spindle.sync_speed.speed = speed;
break;
}
case SPINDLE_TYPE_HUANYANG: huanyang_set(power); break;
default: vfd_spindle_set(power); break;
case SPINDLE_TYPE_HUANYANG:
huanyang_set(power);
break;
default:
vfd_spindle_set(power);
break;
}
}
static void _deinit_cb() {
static void _deinit_cb()
{
spindle.type = spindle.next_type;
spindle.next_type = SPINDLE_TYPE_DISABLED;
switch (spindle.type) {
case SPINDLE_TYPE_DISABLED: break;
case SPINDLE_TYPE_PWM: pwm_init(); break;
case SPINDLE_TYPE_HUANYANG: huanyang_init(); break;
default: vfd_spindle_init(); break;
switch (spindle.type)
{
case SPINDLE_TYPE_DISABLED:
break;
case SPINDLE_TYPE_PWM:
pwm_init();
break;
case SPINDLE_TYPE_HUANYANG:
huanyang_init();
break;
default:
vfd_spindle_init();
break;
}
spindle_update_speed();
}
static void _set_type(spindle_type_t type) {
if (type == spindle.type) return;
static void _set_type(spindle_type_t type)
{
if (type == spindle.type)
return;
spindle_type_t old_type = spindle.type;
spindle.next_type = type;
spindle.type = SPINDLE_TYPE_DISABLED;
switch (old_type) {
case SPINDLE_TYPE_DISABLED: _deinit_cb(); break;
case SPINDLE_TYPE_PWM: pwm_deinit(_deinit_cb); break;
case SPINDLE_TYPE_HUANYANG: huanyang_deinit(_deinit_cb); break;
default: vfd_spindle_deinit(_deinit_cb); break;
switch (old_type)
{
case SPINDLE_TYPE_DISABLED:
_deinit_cb();
break;
case SPINDLE_TYPE_PWM:
pwm_deinit(_deinit_cb);
break;
case SPINDLE_TYPE_HUANYANG:
huanyang_deinit(_deinit_cb);
break;
default:
vfd_spindle_deinit(_deinit_cb);
break;
}
}
spindle_type_t spindle_get_type() { return spindle.type; }
static power_update_t _get_power_update() {
static power_update_t _get_power_update()
{
float power = _speed_to_power(spindle.speed);
// Handle dynamic power
if (state_get() == STATE_RUNNING && spindle.dynamic_power && spindle.inv_feed) {
if (state_get() == STATE_RUNNING && spindle.dynamic_power && spindle.inv_feed)
{
float scale = spindle.inv_feed * exec_get_velocity();
if (scale < 1) power *= scale;
if (scale < 1)
power *= scale;
}
return pwm_get_update(power);
}
void spindle_load_power_updates(power_update_t updates[], float minD,
float maxD) {
float maxD)
{
float stepD = (maxD - minD) * (1.0 / POWER_MAX_UPDATES);
float d = minD + 1e-3; // Starting distance
for (unsigned i = 0; i < POWER_MAX_UPDATES; i++) {
for (unsigned i = 0; i < POWER_MAX_UPDATES; i++)
{
bool changed = false;
d += stepD; // Ending distance for this power step
while (true) {
while (true)
{
// Load new sync speed if needed and available
if (spindle.sync_speed.dist < 0 && command_peek() == COMMAND_sync_speed)
spindle.sync_speed = *(sync_speed_t *)(command_next() + 1);
// Exit if we don't have a speed or it's not ready to be set
if (spindle.sync_speed.dist == -1 || d < spindle.sync_speed.dist) break;
if (spindle.sync_speed.dist == -1 || d < spindle.sync_speed.dist)
break;
// Load sync speed
spindle.sync_speed.dist = -1; // Mark done
@@ -183,127 +216,138 @@ void spindle_load_power_updates(power_update_t updates[], float minD,
changed = true;
}
if (spindle.type == SPINDLE_TYPE_PWM) updates[i] = _get_power_update();
else {
if (spindle.type == SPINDLE_TYPE_PWM)
updates[i] = _get_power_update();
else
{
updates[i].state = POWER_IGNORE;
if (changed) spindle_update_speed();
if (changed)
spindle_update_speed();
}
}
}
// Called from hi-priority stepper interrupt
void spindle_update(const power_update_t &update) { pwm_update(update); }
void spindle_update_speed() { _set_speed(spindle.speed); }
// Called from lo-priority stepper interrupt
void spindle_idle() {
if (spindle.sync_speed.dist != -1) {
void spindle_idle()
{
if (spindle.sync_speed.dist != -1)
{
spindle.sync_speed.dist = -1; // Mark done
spindle.speed = spindle.sync_speed.speed;
if (spindle.type == SPINDLE_TYPE_PWM) spindle_update(_get_power_update());
else spindle_update_speed();
if (spindle.type == SPINDLE_TYPE_PWM)
spindle_update(_get_power_update());
else
spindle_update_speed();
}
}
void spindle_stop() { _set_speed(0); } // Only called when steppers have halted
void spindle_estop() { _set_type(SPINDLE_TYPE_DISABLED); }
// Var callbacks
uint8_t get_tool_type() { return spindle.type; }
void set_tool_type(uint8_t value) { _set_type((spindle_type_t)value); }
bool get_tool_reversed() { return spindle.reversed; }
void set_tool_reversed(bool reversed) {
if (spindle.reversed == reversed) return;
void set_tool_reversed(bool reversed)
{
if (spindle.reversed == reversed)
return;
spindle.reversed = reversed;
spindle_update_speed();
}
float get_speed() { return _get_power() * spindle.max_rpm; }
float get_max_spin() { return spindle.max_rpm; }
void set_max_spin(float value) {
if (spindle.max_rpm != value) {
void set_max_spin(float value)
{
if (spindle.max_rpm != value)
{
spindle.max_rpm = value;
spindle.inv_max_rpm = 1 / value;
spindle_update_speed();
}
}
float get_min_spin() { return spindle.min_rpm; }
void set_min_spin(float value) {
if (spindle.min_rpm != value) {
void set_min_spin(float value)
{
if (spindle.min_rpm != value)
{
spindle.min_rpm = value;
spindle_update_speed();
}
}
uint16_t get_spindle_status() {
switch (spindle.type) {
case SPINDLE_TYPE_DISABLED: return 0;
case SPINDLE_TYPE_PWM: return 0;
case SPINDLE_TYPE_HUANYANG: return huanyang_get_status();
default: return vfd_get_status();
uint16_t get_spindle_status()
{
switch (spindle.type)
{
case SPINDLE_TYPE_DISABLED:
return 0;
case SPINDLE_TYPE_PWM:
return 0;
case SPINDLE_TYPE_HUANYANG:
return huanyang_get_status();
default:
return vfd_get_status();
}
}
uint16_t get_speed_override() { return spindle.override * 1000; }
void set_speed_override(uint16_t value) {
void set_speed_override(uint16_t value)
{
value *= 0.001;
if (spindle.override != value) {
if (spindle.override != value)
{
spindle.override = value;
spindle_update_speed();
}
}
bool get_dynamic_power() { return spindle.dynamic_power; }
void set_dynamic_power(bool enable) {
if (spindle.dynamic_power != enable) {
void set_dynamic_power(bool enable)
{
if (spindle.dynamic_power != enable)
{
spindle.dynamic_power = enable;
spindle_update_speed();
}
}
float get_inverse_feed() { return spindle.inv_feed; }
void set_inverse_feed(float iF) {
if (spindle.inv_feed != iF) {
void set_inverse_feed(float iF)
{
if (spindle.inv_feed != iF)
{
spindle.inv_feed = iF;
spindle_update_speed();
}
}
// Command callbacks
stat_t command_sync_speed(char *cmd) {
stat_t command_sync_speed(char *cmd)
{
sync_speed_t s;
cmd++; // Skip command code
// Get distance and speed
if (!decode_float(&cmd, &s.dist) || s.dist < 0) return STAT_BAD_FLOAT;
if (!decode_float(&cmd, &s.speed)) return STAT_BAD_FLOAT;
if (!decode_float(&cmd, &s.dist) || s.dist < 0)
return STAT_BAD_FLOAT;
if (!decode_float(&cmd, &s.speed))
return STAT_BAD_FLOAT;
// Queue
command_push(COMMAND_sync_speed, &s);
@@ -311,21 +355,21 @@ stat_t command_sync_speed(char *cmd) {
return STAT_OK;
}
unsigned command_sync_speed_size() { return sizeof(sync_speed_t); }
void command_sync_speed_exec(void *data) {
void command_sync_speed_exec(void *data)
{
_set_speed(((sync_speed_t *)data)->speed);
}
stat_t command_speed(char *cmd) {
stat_t command_speed(char *cmd)
{
cmd++; // Skip command code
// Get speed
float speed;
if (!decode_float(&cmd, &speed)) return STAT_BAD_FLOAT;
if (!decode_float(&cmd, &speed))
return STAT_BAD_FLOAT;
// Queue
command_push(COMMAND_speed, &speed);
@@ -333,6 +377,5 @@ stat_t command_speed(char *cmd) {
return STAT_OK;
}
unsigned command_speed_size() { return sizeof(float); }
void command_speed_exec(void *data) { _set_speed(*(float *)data); }

View File

@@ -30,22 +30,22 @@
#include <stdbool.h>
#include <stdint.h>
typedef enum {
typedef enum
{
POWER_IGNORE,
POWER_FORWARD,
POWER_REVERSE
} power_state_t;
typedef struct {
typedef struct
{
power_state_t state;
float power;
uint16_t period; // Used by PWM
} power_update_t;
typedef enum {
typedef enum
{
SPINDLE_TYPE_DISABLED,
SPINDLE_TYPE_PWM,
SPINDLE_TYPE_HUANYANG,
@@ -58,13 +58,10 @@ typedef enum {
SPINDLE_TYPE_SUNFAR_E300,
SPINDLE_TYPE_OMRON_MX2,
SPINDLE_TYPE_V70,
SPINDLE_TYPE_EM60,
} spindle_type_t;
typedef void (*deinit_cb_t)();
spindle_type_t spindle_get_type();
void spindle_stop();
void spindle_estop();

View File

@@ -38,8 +38,8 @@
#include <math.h>
#include <stdint.h>
typedef enum {
typedef enum
{
REG_DISABLED,
REG_CONNECT_WRITE,
@@ -49,7 +49,6 @@ typedef enum {
REG_FREQ_SET,
REG_FREQ_SIGN_SET,
REG_FREQ_SCALED_SET,
REG_STOP_WRITE,
REG_FWD_WRITE,
@@ -64,18 +63,16 @@ typedef enum {
REG_DISCONNECT_WRITE,
} vfd_reg_type_t;
typedef struct {
typedef struct
{
vfd_reg_type_t type;
uint16_t addr;
uint16_t value;
uint8_t fails;
} vfd_reg_t;
#define P(H, L) ((H) << 8 | (L))
// NOTE, Modbus reg = AC Tech reg + 1
const vfd_reg_t ac_tech_regs[] PROGMEM = {
{REG_CONNECT_WRITE, 48, 19}, // Password unlock
@@ -92,7 +89,6 @@ const vfd_reg_t ac_tech_regs[] PROGMEM = {
{REG_DISABLED},
};
const vfd_reg_t nowforever_regs[] PROGMEM = {
{REG_MAX_FREQ_READ, 7, 0}, // Max frequency
{REG_FREQ_SET, 2305, 0}, // Frequency
@@ -104,7 +100,6 @@ const vfd_reg_t nowforever_regs[] PROGMEM = {
{REG_DISABLED},
};
const vfd_reg_t delta_vfd015m21a_regs[] PROGMEM = {
{REG_CONNECT_WRITE, 0x2002, 2}, // Reset fault
{REG_MAX_FREQ_READ, 3, 0}, // Max frequency
@@ -117,7 +112,6 @@ const vfd_reg_t delta_vfd015m21a_regs[] PROGMEM = {
{REG_DISABLED},
};
const vfd_reg_t yl600_regs[] PROGMEM = {
{REG_CONNECT_WRITE, 0x2000, 128}, // Reset all errors
{REG_MAX_FREQ_READ, 0x0004, 0}, // Max frequency
@@ -130,7 +124,6 @@ const vfd_reg_t yl600_regs[] PROGMEM = {
{REG_DISABLED},
};
const vfd_reg_t fr_d700_regs[] PROGMEM = {
{REG_MAX_FREQ_READ, 1000, 0}, // Max frequency
{REG_FREQ_SET, 13, 0}, // Frequency
@@ -141,7 +134,6 @@ const vfd_reg_t fr_d700_regs[] PROGMEM = {
{REG_DISABLED},
};
const vfd_reg_t sunfar_e300_regs[] PROGMEM = {
{REG_CONNECT_WRITE, 0x1001, 32}, // Reset all errors
{REG_MAX_FREQ_READ, 0xf004, 0}, // Max frequency F0.4
@@ -154,7 +146,6 @@ const vfd_reg_t sunfar_e300_regs[] PROGMEM = {
{REG_DISABLED},
};
const vfd_reg_t omron_mx2_regs[] PROGMEM = {
{REG_CONNECT_WRITE, 0x1200, 3}, // A001 Frequency reference modbus
{REG_CONNECT_WRITE, 0x1201, 3}, // A002 Run command modbus
@@ -168,7 +159,6 @@ const vfd_reg_t omron_mx2_regs[] PROGMEM = {
{REG_DISABLED},
};
const vfd_reg_t v70_regs[] PROGMEM = {
{REG_MAX_FREQ_READ, 0x0005, 0}, // Maximum operating frequency
{REG_FREQ_SET, 0x0201, 0}, // Set frequency in 0.1Hz
@@ -180,22 +170,11 @@ const vfd_reg_t v70_regs[] PROGMEM = {
{REG_DISABLED},
};
const vfd_reg_t em60_regs[] PROGMEM = {
{REG_MAX_FREQ_READ, 0x0007, 0}, // Read max frequency
{REG_FREQ_SCALED_SET, 0xa001, 10000}, // Set scaled frequency
{REG_FREQ_READ, 0x9000, 0}, // Read frequency
{REG_FWD_WRITE, 0xa000, 1}, // Run forward
{REG_REV_WRITE, 0xa000, 2}, // Run reverse
{REG_STOP_WRITE, 0xa000, 5}, // Stop
{REG_STATUS_READ, 0xb000, 0}, // Read status
{REG_DISABLED},
};
static vfd_reg_t regs[VFDREG];
static vfd_reg_t custom_regs[VFDREG];
static struct {
static struct
{
vfd_reg_type_t state;
int8_t reg;
uint8_t read_count;
@@ -212,46 +191,52 @@ static struct {
deinit_cb_t deinit_cb;
} vfd;
static void _disconnected() {
static void _disconnected()
{
modbus_deinit();
if (vfd.deinit_cb) vfd.deinit_cb();
if (vfd.deinit_cb)
vfd.deinit_cb();
vfd.deinit_cb = 0;
}
static bool _next_state() {
switch (vfd.state) {
static bool _next_state()
{
switch (vfd.state)
{
case REG_MAX_FREQ_FIXED:
if (!vfd.power) vfd.state = REG_STOP_WRITE;
else vfd.state = REG_FREQ_SET;
break;
case REG_FREQ_SCALED_SET:
if (vfd.power < 0) vfd.state = REG_REV_WRITE;
else if (0 < vfd.power) vfd.state = REG_FWD_WRITE;
else vfd.state = REG_STOP_WRITE;
if (!vfd.power)
vfd.state = REG_STOP_WRITE;
else
vfd.state = REG_FREQ_SET;
break;
case REG_FREQ_SIGN_SET:
if (vfd.power < 0) vfd.state = REG_REV_WRITE;
else if (0 < vfd.power) vfd.state = REG_FWD_WRITE;
else vfd.state = REG_STOP_WRITE;
if (vfd.power < 0)
vfd.state = REG_REV_WRITE;
else if (0 < vfd.power)
vfd.state = REG_FWD_WRITE;
else
vfd.state = REG_STOP_WRITE;
break;
case REG_STOP_WRITE: case REG_FWD_WRITE: case REG_REV_WRITE:
case REG_STOP_WRITE:
case REG_FWD_WRITE:
case REG_REV_WRITE:
vfd.state = REG_FREQ_READ;
break;
case REG_STATUS_READ:
if (vfd.shutdown || estop_triggered()) vfd.state = REG_DISCONNECT_WRITE;
if (vfd.shutdown || estop_triggered())
vfd.state = REG_DISCONNECT_WRITE;
else if (vfd.changed) {
else if (vfd.changed)
{
// Update frequency and state
vfd.changed = false;
vfd.state = REG_MAX_FREQ_READ;
} else {
}
else
{
// Continue querying after delay
vfd.state = REG_FREQ_READ;
vfd.wait = rtc_get_time() + VFD_QUERY_DELAY;
@@ -270,87 +255,113 @@ static bool _next_state() {
return true;
}
static bool _exec_command();
static void _next_reg() {
while (true) {
static void _next_reg()
{
while (true)
{
vfd.reg++;
if (vfd.reg == VFDREG) {
if (vfd.reg == VFDREG)
{
vfd.reg = -1;
vfd.read_count = 0;
if (!_next_state()) break;
} else if (regs[vfd.reg].type == vfd.state && _exec_command()) break;
if (!_next_state())
break;
}
else if (regs[vfd.reg].type == vfd.state && _exec_command())
break;
}
}
static void _connect() {
static void _connect()
{
vfd.state = REG_CONNECT_WRITE;
vfd.reg = -1;
_next_reg();
}
static void _modbus_cb(bool ok, uint16_t addr, uint16_t value) {
static void _modbus_cb(bool ok, uint16_t addr, uint16_t value)
{
// Handle error
if (!ok) {
if (regs[vfd.reg].fails < 255) regs[vfd.reg].fails++;
if (vfd.shutdown || estop_triggered()) _disconnected();
else _connect();
if (!ok)
{
if (regs[vfd.reg].fails < 255)
regs[vfd.reg].fails++;
if (vfd.shutdown || estop_triggered())
_disconnected();
else
_connect();
return;
}
// Handle read result
vfd.read_count++;
switch (regs[vfd.reg].type) {
case REG_MAX_FREQ_READ: vfd.max_freq = value; break;
case REG_FREQ_READ: vfd.actual_power = value / (float)vfd.max_freq; break;
switch (regs[vfd.reg].type)
{
case REG_MAX_FREQ_READ:
vfd.max_freq = value;
break;
case REG_FREQ_READ:
vfd.actual_power = value / (float)vfd.max_freq;
break;
case REG_FREQ_SIGN_READ:
vfd.actual_power = (int16_t)value / (float)vfd.max_freq;
break;
case REG_FREQ_ACTECH_READ:
if (vfd.read_count == 2) vfd.actual_power = value / (float)vfd.max_freq;
if (vfd.read_count < 6) return;
if (vfd.read_count == 2)
vfd.actual_power = value / (float)vfd.max_freq;
if (vfd.read_count < 6)
return;
break;
case REG_STATUS_READ: vfd.status = value; break;
case REG_STATUS_READ:
vfd.status = value;
break;
default: break;
default:
break;
}
// Next
_next_reg();
}
static bool _use_multi_write() {
switch (spindle_get_type()) {
case SPINDLE_TYPE_CUSTOM: return vfd.user_multi_write;
case SPINDLE_TYPE_NOWFOREVER: return true;
default: return false;
static bool _use_multi_write()
{
switch (spindle_get_type())
{
case SPINDLE_TYPE_CUSTOM:
return vfd.user_multi_write;
case SPINDLE_TYPE_NOWFOREVER:
return true;
default:
return false;
}
}
static bool _exec_command() {
if (vfd.wait) return true;
static bool _exec_command()
{
if (vfd.wait)
return true;
vfd_reg_t reg = regs[vfd.reg];
uint16_t words = 1;
bool read = false;
bool write = false;
switch (reg.type) {
case REG_DISABLED: break;
switch (reg.type)
{
case REG_DISABLED:
break;
case REG_MAX_FREQ_FIXED: vfd.max_freq = reg.value; break;
case REG_MAX_FREQ_FIXED:
vfd.max_freq = reg.value;
break;
case REG_FREQ_SET:
write = true;
@@ -362,11 +373,6 @@ static bool _exec_command() {
reg.value = vfd.power * vfd.max_freq;
break;
case REG_FREQ_SCALED_SET:
write = true;
reg.value = fabs(vfd.power) * reg.value;
break;
case REG_CONNECT_WRITE:
case REG_STOP_WRITE:
case REG_FWD_WRITE:
@@ -386,76 +392,100 @@ static bool _exec_command() {
break;
}
if (read) modbus_read(reg.addr, words, _modbus_cb);
else if (write) (_use_multi_write() ? modbus_multi_write : modbus_write)
(reg.addr, reg.value, _modbus_cb);
else return false;
if (read)
modbus_read(reg.addr, words, _modbus_cb);
else if (write)
(_use_multi_write() ? modbus_multi_write : modbus_write)(reg.addr, reg.value, _modbus_cb);
else
return false;
return true;
}
static void _load(const vfd_reg_t *_regs) {
static void _load(const vfd_reg_t *_regs)
{
memset(&regs, 0, sizeof(regs));
for (int i = 0; i < VFDREG; i++) {
for (int i = 0; i < VFDREG; i++)
{
regs[i].type = (vfd_reg_type_t)pgm_read_byte(&_regs[i].type);
if (!regs[i].type) break;
if (!regs[i].type)
break;
regs[i].addr = pgm_read_word(&_regs[i].addr);
regs[i].value = pgm_read_word(&_regs[i].value);
}
}
void vfd_spindle_init() {
void vfd_spindle_init()
{
memset(&vfd, 0, sizeof(vfd));
for (int i = 0; i < VFDREG; i++) regs[i].fails = 0;
for (int i = 0; i < VFDREG; i++)
regs[i].fails = 0;
modbus_init();
switch (spindle_get_type()) {
case SPINDLE_TYPE_CUSTOM: memcpy(regs, custom_regs, sizeof(regs)); break;
case SPINDLE_TYPE_AC_TECH: _load(ac_tech_regs); break;
case SPINDLE_TYPE_NOWFOREVER: _load(nowforever_regs); break;
case SPINDLE_TYPE_DELTA_VFD015M21A: _load(delta_vfd015m21a_regs); break;
case SPINDLE_TYPE_YL600: _load(yl600_regs); break;
case SPINDLE_TYPE_FR_D700: _load(fr_d700_regs); break;
case SPINDLE_TYPE_SUNFAR_E300: _load(sunfar_e300_regs); break;
case SPINDLE_TYPE_OMRON_MX2: _load(omron_mx2_regs); break;
case SPINDLE_TYPE_V70: _load(v70_regs); break;
case SPINDLE_TYPE_EM60: _load(em60_regs); break;
default: break;
switch (spindle_get_type())
{
case SPINDLE_TYPE_CUSTOM:
memcpy(regs, custom_regs, sizeof(regs));
break;
case SPINDLE_TYPE_AC_TECH:
_load(ac_tech_regs);
break;
case SPINDLE_TYPE_NOWFOREVER:
_load(nowforever_regs);
break;
case SPINDLE_TYPE_DELTA_VFD015M21A:
_load(delta_vfd015m21a_regs);
break;
case SPINDLE_TYPE_YL600:
_load(yl600_regs);
break;
case SPINDLE_TYPE_FR_D700:
_load(fr_d700_regs);
break;
case SPINDLE_TYPE_SUNFAR_E300:
_load(sunfar_e300_regs);
break;
case SPINDLE_TYPE_OMRON_MX2:
_load(omron_mx2_regs);
break;
case SPINDLE_TYPE_V70:
_load(v70_regs);
break;
default:
break;
}
_connect();
}
void vfd_spindle_deinit(deinit_cb_t cb) {
void vfd_spindle_deinit(deinit_cb_t cb)
{
vfd.shutdown = true;
vfd.deinit_cb = cb;
}
void vfd_spindle_set(float power) {
void vfd_spindle_set(float power)
{
if (vfd.power != power)
ATOMIC_BLOCK(ATOMIC_RESTORESTATE) {
ATOMIC_BLOCK(ATOMIC_RESTORESTATE)
{
vfd.power = power;
vfd.changed = true;
}
}
float vfd_spindle_get() { return vfd.actual_power; }
uint16_t vfd_get_status() { return vfd.status; }
void vfd_spindle_rtc_callback() {
if (!vfd.wait || !rtc_expired(vfd.wait)) return;
void vfd_spindle_rtc_callback()
{
if (!vfd.wait || !rtc_expired(vfd.wait))
return;
vfd.wait = 0;
_next_reg();
}
// Variable callbacks
uint16_t get_vfd_max_freq() { return vfd.max_freq; }
void set_vfd_max_freq(uint16_t max_freq) { vfd.max_freq = max_freq; }
@@ -463,40 +493,37 @@ bool get_vfd_multi_write() {return vfd.user_multi_write;}
void set_vfd_multi_write(bool value) { vfd.user_multi_write = value; }
uint8_t get_vfd_reg_type(int reg) { return regs[reg].type; }
void set_vfd_reg_type(int reg, uint8_t type) {
void set_vfd_reg_type(int reg, uint8_t type)
{
custom_regs[reg].type = (vfd_reg_type_t)type;
if (spindle_get_type() == SPINDLE_TYPE_CUSTOM)
regs[reg].type = custom_regs[reg].type;
vfd.changed = true;
}
uint16_t get_vfd_reg_addr(int reg) { return regs[reg].addr; }
void set_vfd_reg_addr(int reg, uint16_t addr) {
void set_vfd_reg_addr(int reg, uint16_t addr)
{
custom_regs[reg].addr = addr;
if (spindle_get_type() == SPINDLE_TYPE_CUSTOM)
regs[reg].addr = custom_regs[reg].addr;
vfd.changed = true;
}
uint16_t get_vfd_reg_val(int reg) { return regs[reg].value; }
void set_vfd_reg_val(int reg, uint16_t value) {
void set_vfd_reg_val(int reg, uint16_t value)
{
custom_regs[reg].value = value;
if (spindle_get_type() == SPINDLE_TYPE_CUSTOM)
regs[reg].value = custom_regs[reg].value;
vfd.changed = true;
}
uint8_t get_vfd_reg_fails(int reg) { return regs[reg].fails; }
void set_vfd_reg_fails(int reg, uint8_t value) {
void set_vfd_reg_fails(int reg, uint8_t value)
{
regs[reg].fails = value;
}

View File

@@ -7,14 +7,14 @@ module.exports = {
computed: {
has_user_value: function () {
const type = this.model["reg-type"];
return type.includes("write") || type.includes("fixed") || type.includes("scaled");
}
var type = this.model["reg-type"];
return type.indexOf("write") != -1 || type.indexOf("fixed") != -1;
},
},
methods: {
change: function () {
this.$dispatch("input-changed");
}
}
},
},
};

View File

@@ -82,22 +82,18 @@ module.exports = {
name: "OMRON MX2",
unsupported: true,
},
{
id: "EM60",
name: "EM60",
},
],
};
},
components: {
"modbus-reg": require("./modbus-reg.js")
"modbus-reg": require("./modbus-reg.js"),
},
watch: {
"state.mr": function () {
this.value = this.state.mr;
}
},
},
events: {
@@ -144,7 +140,7 @@ module.exports = {
modbus_status: function () {
return modbus.status_to_string(this.state.mx);
}
},
},
methods: {
@@ -152,10 +148,20 @@ module.exports = {
const selectedToolSettings = this.config["selected-tool-settings"] || {};
const settings = selectedToolSettings[this.selected_tool] || {};
this.config.tool = merge({}, this.config.tool, settings["tool"]);
this.config["pwm-spindle"] = merge({}, this.config["pwm-spindle"], settings["pwm-spindle"]);
this.config["modbus-spindle"] = merge({}, this.config["modbus-spindle"], settings["modbus-spindle"]);
this.config["pwm-spindle"] = merge(
{},
this.config["pwm-spindle"],
settings["pwm-spindle"]
);
this.config["modbus-spindle"] = merge(
{},
this.config["modbus-spindle"],
settings["modbus-spindle"]
);
const tool = this.toolList.find(tool => tool.id == this.config.tool["selected-tool"]);
const tool = this.toolList.find(
(tool) => tool.id == this.config.tool["selected-tool"]
);
this.config.tool["tool-type"] = tool.type || tool.name;
this.$dispatch("config-changed");
@@ -203,7 +209,10 @@ module.exports = {
},
show_modbus_field: function (key) {
return key != "regs" && (key != "multi-write" || this.tool_type == "CUSTOM MODBUS VFD");
return (
key != "regs" &&
(key != "multi-write" || this.tool_type == "CUSTOM MODBUS VFD")
);
},
read: function (e) {
@@ -251,6 +260,6 @@ module.exports = {
for (let reg = 0; reg < regs.length; reg++) {
this.$dispatch("send", `$${reg}vr=0`);
}
}
}
},
},
};

View File

@@ -43,7 +43,7 @@ script#tool-view-template(type="text/x-template")
label.units RPM
fieldset.modbus-program(
v-if="is_modbus && tool_type != 'HUANYANG VFD' && tool_type != 'EM60'")
v-if="is_modbus && this.tool_type != 'HUANYANG VFD'")
h2 Active Modbus Program
p(v-if="$root.modified")
| (Click #[tt(class="save") Save] to activate the selected
@@ -380,64 +380,3 @@ script#tool-view-template(type="text/x-template")
|
| and spindle type. The VFD must be rebooted after changing
| the above settings.
.notes(v-if="tool_type.startsWith('EM60')")
h2 Notes
p Set the following using the VFD's front panel.
table.modbus-regs.fixed-regs
tr
th Address
th Value
th Meaning
th Description
tr
td.reg-addr P0.0.03
td.reg-value 2
td Modbus
td Control mode
tr
td.reg-addr P0.0.04
td.reg-value 9
td Modbus
td Frequency source A
tr
td.reg-addr P0.1.00
td.reg-value 0
td Source A
td Frequency source
tr
td.reg-addr P4.1.00
td.reg-value 3
td 9600 BAUD
td Must match #[tt baud] above
tr
td.reg-addr P4.1.01
td.reg-value 0
td 8N2
td Data format
tr
td.reg-addr P4.1.02
td.reg-value 1
td Bus id
td Must match #[tt bus-id] above
tr
td.reg-addr P4.1.03
td.reg-value 2
td No delay
td Communications response delay
tr
td.reg-addr P4.1.04
td.reg-value 0
td No timeout
td Communications timeout
tr
td.reg-addr P4.1.05
td.reg-value 1
td RTU
td Modbus format
p
| Other settings according to the
|
a(href="https://buildbotics.com/upload/vfd/em60.pdf",
target="_blank") EM60 VFD manual

View File

@@ -270,8 +270,7 @@
"YL600, YL620, YL620-A VFD (Beta)",
"FR-D700 (Beta)",
"Sunfar E300 (Beta)",
"OMRON MX2",
"EM60"
"OMRON MX2"
],
"default": "Disabled",
"code": "st"
@@ -365,7 +364,6 @@
"max-freq-fixed",
"freq-set",
"freq-signed-set",
"freq-scaled-set",
"stop-write",
"forward-write",
"reverse-write",