Added Custom Modbus VFD programming. Fixed config checkbox not displaying defaulted...
authorJoseph Coffland <joseph@cauldrondevelopment.com>
Wed, 18 Apr 2018 10:12:54 +0000 (03:12 -0700)
committerJoseph Coffland <joseph@cauldrondevelopment.com>
Wed, 18 Apr 2018 10:12:54 +0000 (03:12 -0700)
77 files changed:
CHANGELOG.md
Makefile
package.json
src/avr/Makefile
src/avr/src/command.c
src/avr/src/command.def
src/avr/src/command.json.in
src/avr/src/config.h
src/avr/src/drv8711.c
src/avr/src/estop.c
src/avr/src/exec.c
src/avr/src/exec.h
src/avr/src/huanyang.c [new file with mode: 0644]
src/avr/src/huanyang.h [new file with mode: 0644]
src/avr/src/jog.c
src/avr/src/line.c
src/avr/src/messages.def
src/avr/src/modbus.c
src/avr/src/modbus.h
src/avr/src/motor.c
src/avr/src/motor.h
src/avr/src/pwm_spindle.c
src/avr/src/pwm_spindle.h
src/avr/src/report.c
src/avr/src/report.h
src/avr/src/rtc.c
src/avr/src/spindle.c
src/avr/src/spindle.def [deleted file]
src/avr/src/spindle.h
src/avr/src/state.c
src/avr/src/status.c
src/avr/src/stepper.c
src/avr/src/stepper.h
src/avr/src/type.c
src/avr/src/type.h
src/avr/src/util.c
src/avr/src/util.h
src/avr/src/vars.c
src/avr/src/vars.def
src/avr/src/vars.h
src/avr/src/vars.json.in
src/avr/src/vfd/huanyang.c [deleted file]
src/avr/src/vfd/huanyang.h [deleted file]
src/avr/src/vfd/yl600.c [deleted file]
src/avr/src/vfd_spindle.c [new file with mode: 0644]
src/avr/src/vfd_spindle.h [new file with mode: 0644]
src/avr/src/vfd_test.c [new file with mode: 0644]
src/avr/src/vfd_test.h [new file with mode: 0644]
src/jade/templates/cheat-sheet-view.jade
src/jade/templates/gcode-view.jade
src/jade/templates/indicators.jade
src/jade/templates/io-view.jade
src/jade/templates/modbus-reg-view.jade [new file with mode: 0644]
src/jade/templates/motor-view.jade
src/jade/templates/templated-input.jade
src/jade/templates/tool-view.jade
src/js/app.js
src/js/control-view.js
src/js/gauge.js [deleted file]
src/js/gcode-view.js
src/js/indicators.js
src/js/io-view.js
src/js/modbus-reg.js [new file with mode: 0644]
src/js/modbus.js [new file with mode: 0644]
src/js/motor-view.js
src/js/tool-view.js
src/py/bbctrl/Cmd.py
src/py/bbctrl/Comm.py
src/py/bbctrl/CommandQueue.py
src/py/bbctrl/Config.py
src/py/bbctrl/I2C.py
src/py/bbctrl/Mach.py
src/py/bbctrl/Planner.py
src/py/bbctrl/Web.py
src/resources/config-template.json
src/resources/js/gauge.min.js [deleted file]
src/stylus/style.styl

index 4c5895c7f1c69a4e18ed14fe3641efecd19e1931..df8a88f3d067849799f3bb201d059e944f6cd5a3 100644 (file)
@@ -1,13 +1,19 @@
 Buildbotics CNC Controller Firmware Changelog
 ==============================================
 
+## v0.3.22
+ - Fix position loss after program pause.  #130
+ - Correctly handle disabled axes.
+ - Fixed config checkbox not displaying defaulted enabled correctly.
+ - Added Custom Modbus VFD programming.
+
 ## v0.3.21
  - Implemented M70-M73 modal state save/restore.
  - Added support for modbus VFDs.
  - Start Huanyang spindle with out first pressing Start button on VFD.
  - Faster switching of large GCode files in Web.
  - Fixed reported gcode line off by one.
- - Disable MDI while running.
+ - Disable MDI input while running.
  - Stablized direction pin output during slow moves.
 
 ## v0.3.20
index 60a13b58356aef6e79cf4d03455867c02851281d..2810fe13dd6e6c9d93746b22d223750b211b1117 100644 (file)
--- a/Makefile
+++ b/Makefile
@@ -80,7 +80,7 @@ $(GPLAN_IMG):
 
 .PHONY: $(AVR_FIRMWARE)
 $(AVR_FIRMWARE):
-       $(MAKE) -C src/avr $(shell basename $@)
+       $(MAKE) -C src/avr
 
 publish: pkg
        echo -n $(VERSION) > dist/latest.txt
index 674f55c98de04f3d581be40f46c0c617263fb51a..4678b1532e54ea5e88b366b491b80b1fb2a49cac 100644 (file)
@@ -1,6 +1,6 @@
 {
   "name": "bbctrl",
-  "version": "0.3.21.1",
+  "version": "0.3.22",
   "homepage": "http://buildbotics.com/",
   "repository": "https://github.com/buildbotics/bbctrl-firmware",
   "license": "GPL-3.0+",
index 122921dce2ad18ee88f8ca1d6babff1029a3b84b..dc490c4239180f4b3cdc470af2421adb429b1701 100644 (file)
@@ -11,13 +11,13 @@ OBJ := $(patsubst src/vfd/%.c,build/vfd/%.o,$(OBJ))
 JSON = vars command messages
 JSON := $(patsubst %,build/%.json,$(JSON))
 
+all: $(PROJECT).hex $(JSON) size
+
 include Makefile.common
 
 CFLAGS += -Isrc
 
 # Build
-all: $(PROJECT).hex $(JSON) size
-
 $(PROJECT).elf: $(OBJ)
        $(CC) $(LDFLAGS) $(OBJ) $(LIBS) -o $@
 
index ec8229d6fd2d4b9b290906b83d373d4331c83446..257285ee585f2be78e20a87255655a9b0caaaf88 100644 (file)
@@ -29,7 +29,6 @@
 
 #include "usart.h"
 #include "hardware.h"
-#include "report.h"
 #include "vars.h"
 #include "estop.h"
 #include "i2c.h"
@@ -79,7 +78,7 @@ static struct {
 
 
 // Define command callbacks
-#define CMD(CODE, NAME, SYNC, ...)              \
+#define CMD(CODE, NAME, SYNC)                   \
   stat_t command_##NAME(char *);                \
   IF(SYNC)(unsigned command_##NAME##_size();)   \
   IF(SYNC)(void command_##NAME##_exec(void *);)
@@ -87,10 +86,9 @@ static struct {
 #undef CMD
 
 
-// Help & name
-#define CMD(CODE, NAME, SYNC, HELP)                          \
-  static const char command_##NAME##_name[] PROGMEM = #NAME; \
-  static const char command_##NAME##_help[] PROGMEM = HELP;
+// Name
+#define CMD(CODE, NAME, SYNC)                                   \
+  static const char command_##NAME##_name[] PROGMEM = #NAME;
 #include "command.def"
 #undef CMD
 
@@ -144,7 +142,10 @@ static void _exec_cb(char code, uint8_t *data) {
 }
 
 
-static void _i2c_cb(uint8_t *data, uint8_t length) {_dispatch((char *)data);}
+static void _i2c_cb(uint8_t *data, uint8_t length) {
+  stat_t status = _dispatch((char *)data);
+  if (status) STATUS_ERROR(status, "i2c: %s", data);
+}
 
 
 void command_init() {i2c_set_read_callback(_i2c_cb);}
@@ -154,12 +155,11 @@ unsigned command_get_count() {return cmd.count;}
 
 void command_print_json() {
   bool first = true;
-  static const char fmt[] PROGMEM =
-    "\"%c\":{\"name\":\"%" PRPSTR "\",\"help\":\"%" PRPSTR "\"}";
+  static const char fmt[] PROGMEM = "\"%c\":{\"name\":\"%" PRPSTR "\"}";
 
-#define CMD(CODE, NAME, SYNC, HELP)                                     \
+#define CMD(CODE, NAME, SYNC)                                           \
   if (first) first = false; else putchar(',');                          \
-  printf_P(fmt, CODE, command_##NAME##_name, command_##NAME##_help);
+  printf_P(fmt, CODE, command_##NAME##_name);
 
 #include "command.def"
 #undef CMD
@@ -207,9 +207,6 @@ bool command_callback() {
 
   block = 0; // Command consumed
 
-  // Reporting
-  report_request();
-
   switch (status) {
   case STAT_OK: break;
   case STAT_NOP: break;
@@ -257,8 +254,6 @@ bool command_exec() {
   if (!exec_get_velocity() && cmd.count < EXEC_FILL_TARGET &&
       !rtc_expired(cmd.last_empty + EXEC_DELAY)) return false;
 
-  if (state_get() == STATE_HOLDING) return false;
-
   char code = (char)sync_q_next();
   unsigned size = _size(code);
 
@@ -270,7 +265,6 @@ bool command_exec() {
   state_running();
 
   _exec_cb(code, data);
-  report_request();
 
   return true;
 }
index 680990d1fd239502e59558d5e73bd83521658a07..f1b5f7dd7773519df35bb0b637af7a6cbac4f456 100644 (file)
 
 \******************************************************************************/
 
-CMD('$', var,       0, "Set or get variable")
-CMD('#', sync_var,  1, "Set variable synchronous")
-CMD('s', seek,      1, "[switch][flags:active|error]")
-CMD('a', set_axis,  1, "[axis][position] Set axis position")
-CMD('l', line,      1, "[targetVel][maxJerk][axes][times]")
-CMD('I', input,     1, "[a|d][port][mode][timeout] Read input")
-CMD('d', dwell,     1, "[seconds]")
-CMD('P', pause,     1, "[type] Pause control")
-CMD('S', stop,      0, "Stop move, spindle and load outputs")
-CMD('U', unpause,   0, "Unpause")
-CMD('j', jog,       0, "[axes]")
-CMD('r', report,    0, "<0|1>[var] Enable or disable var reporting")
-CMD('R', reboot,    0, "Reboot the controller")
-CMD('c', resume,    0, "Continue processing after a flush")
-CMD('E', estop,     0, "Emergency stop")
-CMD('C', clear,     0, "Clear estop")
-CMD('F', flush,     0, "Flush command queue")
-CMD('D', dump,      0, "Report all variables")
-CMD('h', help,      0, "Print this help screen")
+//(CODE, NAME,      SYNC)
+CMD('$', var,          0) // Set or get variable
+CMD('#', sync_var,     1) // Set variable synchronous
+CMD('m', modbus_read,  1) // [addr]
+CMD('M', modbus_write, 1) // [addr][value]
+CMD('s', seek,         1) // [switch][flags:active|error]
+CMD('a', set_axis,     1) // [axis][position] Set axis position
+CMD('l', line,         1) // [targetVel][maxJerk][axes][times]
+CMD('I', input,        1) // [a|d][port][mode][timeout] Read input
+CMD('d', dwell,        1) // [seconds]
+CMD('P', pause,        1) // [type] Pause control
+CMD('S', stop,         0) // Stop move, spindle and load outputs
+CMD('U', unpause,      0) // Unpause
+CMD('j', jog,          0) // [axes]
+CMD('r', report,       0) // <0|1>[var] Enable or disable var reporting
+CMD('R', reboot,       0) // Reboot the controller
+CMD('c', resume,       0) // Continue processing after a flush
+CMD('E', estop,        0) // Emergency stop
+CMD('C', clear,        0) // Clear estop
+CMD('F', flush,        0) // Flush command queue
+CMD('D', dump,         0) // Report all variables
+CMD('h', help,         0) // Print this help screen
index dbb22637510504bd1903f31abf8778cd2993512a..9e51ea913f5818da0c1a331b2a55d1325dc95f00 100644 (file)
@@ -1,10 +1,9 @@
 #include "cpp_magic.h"
 {
-#define CMD(CODE, NAME, SYNC, HELP) \
+#define CMD(CODE, NAME, SYNC) \
   #NAME: {                                      \
     "code": CODE,                               \
-    "sync": IF_ELSE(SYNC)(true, false),         \
-    "help": HELP                                \
+    "sync": IF_ELSE(SYNC)(true, false)          \
   },
 #include "command.def"
 #undef CMD
index 483d6cf1c29d76fa67f43989b9375b017036810b..eb254c3e5d2dc146028e477aaae1800a07529f74 100644 (file)
@@ -91,22 +91,22 @@ enum {
   PROBE_PIN,
 };
 
-#define SPI_SS_PIN SERIAL_CTS_PIN // Needed for SPI configuration
+#define SPI_SS_PIN               SERIAL_CTS_PIN // Needed for SPI configuration
 
 
 #define AXES                     6 // number of axes
 #define MOTORS                   4 // number of motors on the board
 #define OUTS                     5 // number of supported pin outputs
 #define ANALOG                   2 // number of supported analog inputs
-
+#define VFDREG                  32 // number of supported VFD modbus registers
 
 // Switch settings.  See switch.c
-#define SWITCH_DEBOUNCE 5 // ms
+#define SWITCH_DEBOUNCE          5 // ms
 
 
 // Motor ISRs
-#define STALL_ISR_vect PORTA_INT1_vect
-#define FAULT_ISR_vect PORTF_INT1_vect
+#define STALL_ISR_vect           PORTA_INT1_vect
+#define FAULT_ISR_vect           PORTF_INT1_vect
 
 
 /* Interrupt usage:
@@ -122,91 +122,95 @@ enum {
  *        in a permanent loop call in usart_putc() (usart.c).
  */
 
-// Timer assignments - see specific modules for details
-// TCC1 free
-#define TIMER_STEP             TCC0 // Step timer    (see stepper.h)
-#define TIMER_PWM              TCD1 // PWM timer     (see pwm_spindle.c)
+// Timer assignments
+// NOTE, TCC1 free
+#define TIMER_STEP               TCC0 // Step timer (see stepper.h)
+#define TIMER_PWM                TCD1 // PWM timer  (see pwm_spindle.c)
 
-#define M1_TIMER               TCD0
-#define M2_TIMER               TCE0
-#define M3_TIMER               TCF0
-#define M4_TIMER               TCE1
+#define M1_TIMER                 TCD0
+#define M2_TIMER                 TCE0
+#define M3_TIMER                 TCF0
+#define M4_TIMER                 TCE1
 
-#define M1_DMA_CH              DMA.CH0
-#define M2_DMA_CH              DMA.CH1
-#define M3_DMA_CH              DMA.CH2
-#define M4_DMA_CH              DMA.CH3
+#define M1_DMA_CH                DMA.CH0
+#define M2_DMA_CH                DMA.CH1
+#define M3_DMA_CH                DMA.CH2
+#define M4_DMA_CH                DMA.CH3
 
-#define M1_DMA_TRIGGER         DMA_CH_TRIGSRC_TCD0_CCA_gc
-#define M2_DMA_TRIGGER         DMA_CH_TRIGSRC_TCE0_CCA_gc
-#define M3_DMA_TRIGGER         DMA_CH_TRIGSRC_TCF0_CCA_gc
-#define M4_DMA_TRIGGER         DMA_CH_TRIGSRC_TCE1_CCA_gc
+#define M1_DMA_TRIGGER           DMA_CH_TRIGSRC_TCD0_CCA_gc
+#define M2_DMA_TRIGGER           DMA_CH_TRIGSRC_TCE0_CCA_gc
+#define M3_DMA_TRIGGER           DMA_CH_TRIGSRC_TCF0_CCA_gc
+#define M4_DMA_TRIGGER           DMA_CH_TRIGSRC_TCE1_CCA_gc
 
 
 // Timer setup for stepper and dwells
-#define STEP_TIMER_ENABLE      TC_CLKSEL_DIV8_gc
-#define STEP_TIMER_DIV         8
-#define STEP_TIMER_FREQ        (F_CPU / STEP_TIMER_DIV)
-#define STEP_TIMER_POLL        ((uint16_t)(STEP_TIMER_FREQ * 0.001)) // 1ms
-#define STEP_TIMER_WGMODE      TC_WGMODE_NORMAL_gc // count to TOP & rollover
-#define STEP_TIMER_ISR         TCC0_OVF_vect
-#define STEP_TIMER_INTLVL      TC_OVFINTLVL_HI_gc
-#define STEP_LOW_LEVEL_ISR     ADCB_CH0_vect
-#define STEP_PULSE_WIDTH       (F_CPU * 0.000002 / 2) // 2uS w/ clk/2
-
-#define SEGMENT_TIME           (0.004 / 60.0) // mins
+#define STEP_TIMER_ENABLE        TC_CLKSEL_DIV8_gc
+#define STEP_TIMER_DIV           8
+#define STEP_TIMER_FREQ          (F_CPU / STEP_TIMER_DIV)
+#define STEP_TIMER_POLL          ((uint16_t)(STEP_TIMER_FREQ * 0.001)) // 1ms
+#define STEP_TIMER_WGMODE        TC_WGMODE_NORMAL_gc // count to TOP & rollover
+#define STEP_TIMER_ISR           TCC0_OVF_vect
+#define STEP_TIMER_INTLVL        TC_OVFINTLVL_HI_gc
+#define STEP_LOW_LEVEL_ISR       ADCB_CH0_vect
+#define STEP_PULSE_WIDTH         (F_CPU * 0.000002 / 2) // 2uS w/ clk/2
+#define SEGMENT_TIME             (0.004 / 60.0) // mins
 
 
 // DRV8711 settings
-#define DRV8711_OFF   12
-#define DRV8711_BLANK (0x32 | DRV8711_BLANK_ABT_bm)
-#define DRV8711_DECAY (DRV8711_DECAY_DECMOD_MIXED | 16)
-
-#define DRV8711_STALL (DRV8711_STALL_SDCNT_2 | DRV8711_STALL_VDIV_4 | 200)
-#define DRV8711_DRIVE (DRV8711_DRIVE_IDRIVEP_50 |                       \
-                       DRV8711_DRIVE_IDRIVEN_100 | DRV8711_DRIVE_TDRIVEP_250 | \
-                       DRV8711_DRIVE_TDRIVEN_250 | DRV8711_DRIVE_OCPDEG_1 | \
-                       DRV8711_DRIVE_OCPTH_250)
-#define DRV8711_TORQUE DRV8711_TORQUE_SMPLTH_200
-#define DRV8711_CTRL  (DRV8711_CTRL_ISGAIN_10 | DRV8711_CTRL_DTIME_450 | \
-                       DRV8711_CTRL_EXSTALL_bm)
+#define DRV8711_OFF              12
+#define DRV8711_BLANK            (0x32 | DRV8711_BLANK_ABT_bm)
+#define DRV8711_DECAY            (DRV8711_DECAY_DECMOD_MIXED | 16)
+
+#define DRV8711_STALL            (DRV8711_STALL_SDCNT_2 |      \
+                                  DRV8711_STALL_VDIV_4 | 200)
+#define DRV8711_DRIVE            (DRV8711_DRIVE_IDRIVEP_50  | \
+                                  DRV8711_DRIVE_IDRIVEN_100 | \
+                                  DRV8711_DRIVE_TDRIVEP_250 | \
+                                  DRV8711_DRIVE_TDRIVEN_250 | \
+                                  DRV8711_DRIVE_OCPDEG_1    | \
+                                  DRV8711_DRIVE_OCPTH_250)
+#define DRV8711_TORQUE            DRV8711_TORQUE_SMPLTH_200
+#define DRV8711_CTRL             (DRV8711_CTRL_ISGAIN_10 | \
+                                  DRV8711_CTRL_DTIME_450 | \
+                                  DRV8711_CTRL_EXSTALL_bm)
 
 
 // RS485 settings
-#define RS485_PORT             USARTD1
-#define RS485_DRE_vect         USARTD1_DRE_vect
-#define RS485_TXC_vect         USARTD1_TXC_vect
-#define RS485_RXC_vect         USARTD1_RXC_vect
+#define RS485_PORT               USARTD1
+#define RS485_DRE_vect           USARTD1_DRE_vect
+#define RS485_TXC_vect           USARTD1_TXC_vect
+#define RS485_RXC_vect           USARTD1_RXC_vect
 
 
 // Modbus settings
-#define MODBUS_TIMEOUT         50 // ms. response timeout
-#define MODBUS_RETRIES          4 // Number of retries before failure
-#define MODBUS_BUF_SIZE        64 // Max bytes in rx/tx buffers
-
+#define MODBUS_TIMEOUT           50  // ms. response timeout
+#define MODBUS_RETRIES           4   // Number of retries before failure
+#define MODBUS_BUF_SIZE          8   // Max bytes in rx/tx buffers
+#define VFD_QUERY_DELAY          100 // ms
 
 // Serial settings
-#define SERIAL_BAUD            USART_BAUD_115200
-#define SERIAL_PORT            USARTC0
-#define SERIAL_DRE_vect        USARTC0_DRE_vect
-#define SERIAL_RXC_vect        USARTC0_RXC_vect
-#define SERIAL_CTS_THRESH      4
+#define SERIAL_BAUD              USART_BAUD_115200
+#define SERIAL_PORT              USARTC0
+#define SERIAL_DRE_vect          USARTC0_DRE_vect
+#define SERIAL_RXC_vect          USARTC0_RXC_vect
+#define SERIAL_CTS_THRESH        4
 
 
 // Input
-#define INPUT_BUFFER_LEN       128 // text buffer size (255 max)
+#define INPUT_BUFFER_LEN         128 // text buffer size (255 max)
 
 
-// I2C
-#define I2C_DEV                 TWIC
-#define I2C_ISR                 TWIC_TWIS_vect
-#define I2C_ADDR                0x2b
-#define I2C_MAX_DATA            8
+// Report
+#define REPORT_RATE              250 // ms
 
+// I2C
+#define I2C_DEV                  TWIC
+#define I2C_ISR                  TWIC_TWIS_vect
+#define I2C_ADDR                 0x2b
+#define I2C_MAX_DATA             8
 
-// Settings ********************************************************************
 
-// Motor settings.  See motor.c
+// Motor
 #define MOTOR_IDLE_TIMEOUT       0.25  // secs, motor off after this time
 #define MIN_STEP_CORRECTION      2
 
index e05ac519645ae2f22343d678979addfec3f74182..69e0a666161eefae973032c060e8daa54cbb97ec 100644 (file)
@@ -29,7 +29,6 @@
 #include "status.h"
 #include "stepper.h"
 #include "switch.h"
-#include "report.h"
 
 #include <avr/interrupt.h>
 #include <util/delay.h>
@@ -176,10 +175,8 @@ static uint8_t _spi_next_command(uint8_t cmd) {
       case DRV8711_STATUS_REG:
         drv->status = spi.responses[driver];
 
-        if ((drv->status & drv->flags) != drv->status) {
+        if ((drv->status & drv->flags) != drv->status)
           drv->flags |= drv->status;
-          report_request();
-        }
         break;
 
       case DRV8711_OFF_REG:
@@ -510,6 +507,4 @@ void command_mreset(int argc, char *argv[]) {
     int driver = atoi(argv[1]);
     if (driver < DRIVERS) drivers[driver].flags = 0;
   }
-
-  report_request();
 }
index be2aebc4f75b623990071d4908ac150d7d10a663..de822fed369e62b9a49ced83abb0e82cb8078d30 100644 (file)
@@ -30,7 +30,6 @@
 #include "stepper.h"
 #include "spindle.h"
 #include "switch.h"
-#include "report.h"
 #include "hardware.h"
 #include "config.h"
 #include "state.h"
@@ -99,8 +98,6 @@ void estop_trigger(stat_t reason) {
 
   // Save reason
   _set_reason(reason);
-
-  report_request();
 }
 
 
index 3daad8409b667a15cc411161f2f001e0c0621026..9c8a01fb1cc7fdb99cc945e0969316515d526f67 100644 (file)
 #include "axis.h"
 #include "util.h"
 #include "command.h"
-#include "report.h"
 #include "switch.h"
 #include "seek.h"
 #include "estop.h"
 #include "state.h"
 #include "config.h"
+#include "SCurve.h"
 
 
 static struct {
@@ -51,7 +51,17 @@ static struct {
   float peak_accel;
 
   float feed_override;
-  float spindle_override;
+
+  struct {
+    float target[AXES];
+    float time;
+    float vel;
+    float accel;
+    float max_vel;
+    float max_accel;
+    float max_jerk;
+    exec_cb_t cb;
+  } seg;
 } ex;
 
 
@@ -63,9 +73,7 @@ static void _limit_switch_cb(switch_id_t sw, bool active) {
 
 void exec_init() {
   memset(&ex, 0, sizeof(ex));
-  ex.feed_override = 1;
-  ex.spindle_override = 1;
-  // TODO implement overrides
+  ex.feed_override = 1; // TODO implement feed override
 
   // Set callback for limit switches
   for (int sw = SW_MIN_X; sw <= SW_MAX_A; sw++)
@@ -101,8 +109,7 @@ void exec_set_jerk(float j) {ex.jerk = j;}
 void exec_set_cb(exec_cb_t cb) {ex.cb = cb;}
 
 
-void exec_move_to_target(float time, const float target[]) {
-  ASSERT(isfinite(time));
+void exec_move_to_target(const float target[]) {
   ASSERT(isfinite(target[AXIS_X]) && isfinite(target[AXIS_Y]) &&
          isfinite(target[AXIS_Z]) && isfinite(target[AXIS_A]) &&
          isfinite(target[AXIS_B]) && isfinite(target[AXIS_C]));
@@ -111,15 +118,98 @@ void exec_move_to_target(float time, const float target[]) {
   copy_vector(ex.position, target);
 
   // Call the stepper prep function
-  st_prep_line(time, target);
+  st_prep_line(target);
+}
+
+
+stat_t _segment_exec() {
+  float t = ex.seg.time;
+  float v = ex.seg.vel;
+  float a = ex.seg.accel;
+
+  // Handle pause
+  if (state_get() == STATE_STOPPING) {
+    a = SCurve::nextAccel(SEGMENT_TIME, 0, ex.velocity, ex.accel,
+                          ex.seg.max_accel, ex.seg.max_jerk);
+    v = ex.velocity + SEGMENT_TIME * a;
+    t *= ex.seg.vel / v;
+    if (v <= 0) t = v = 0;
+
+    if (v < MIN_VELOCITY) {
+      t = v = 0;
+      ex.seg.cb = 0;
+      command_reset_position();
+      state_holding();
+      seek_end();
+    }
+  }
+
+  // Wait for next seg if time is too short and we are still moving
+  if (t < SEGMENT_TIME && (!t || v)) {
+    if (!v) ex.velocity = ex.accel = ex.jerk = 0;
+    ex.cb = ex.seg.cb;
+    return STAT_AGAIN;
+  }
+
+  // Update velocity and accel
+  ex.velocity = v;
+  ex.accel = a;
+
+  if (t <= SEGMENT_TIME) {
+    // Move
+    exec_move_to_target(ex.seg.target);
+    ex.seg.time = 0;
+
+  } else {
+    // Compute next target
+    float ratio = SEGMENT_TIME / t;
+    float target[AXES];
+    for (int axis = 0; axis < AXES; axis++) {
+      float diff = ex.seg.target[axis] - ex.position[axis];
+      target[axis] = ex.position[axis] + ratio * diff;
+    }
+
+    // Move
+    exec_move_to_target(target);
+
+    // Update time
+    if (t == ex.seg.time) ex.seg.time -= SEGMENT_TIME;
+    else ex.seg.time -= SEGMENT_TIME * v / ex.seg.vel;
+  }
+
+  // Check switch
+  if (seek_switch_found()) state_seek_hold();
+
+  return STAT_OK;
+}
+
+
+stat_t exec_segment(float time, const float target[], float vel, float accel,
+                    float maxVel, float maxAccel, float maxJerk) {
+  ASSERT(time <= SEGMENT_TIME);
+
+  copy_vector(ex.seg.target, target);
+  ex.seg.time += time;
+  ex.seg.vel = vel;
+  ex.seg.accel = accel;
+  ex.seg.max_vel = maxVel;
+  ex.seg.max_accel = maxAccel;
+  ex.seg.max_jerk = maxJerk;
+  ex.seg.cb = ex.cb;
+  ex.cb = _segment_exec;
+
+  if (!ex.seg.cb) seek_end();
+
+  return _segment_exec();
 }
 
 
 stat_t exec_next() {
-  // Hold if we've reached zero velocity between commands an stopping
+  // Hold if we've reached zero velocity between commands and stopping
   if (!ex.cb && !exec_get_velocity() && state_get() == STATE_STOPPING)
     state_holding();
 
+  if (state_get() == STATE_HOLDING) return STAT_NOP;
   if (!ex.cb && !command_exec()) return STAT_NOP; // Queue empty
   if (!ex.cb) return STAT_AGAIN; // Non-exec command
   return ex.cb(); // Exec
@@ -135,10 +225,8 @@ float get_peak_vel() {return ex.peak_vel / VELOCITY_MULTIPLIER;}
 void set_peak_vel(float x) {ex.peak_vel = 0;}
 float get_peak_accel() {return ex.peak_accel / ACCEL_MULTIPLIER;}
 void set_peak_accel(float x) {ex.peak_accel = 0;}
-float get_feed_override() {return ex.feed_override;}
-void set_feed_override(float value) {ex.feed_override = value;}
-float get_speed_override() {return ex.spindle_override;}
-void set_speed_override(float value) {ex.spindle_override = value;}
+uint16_t get_feed_override() {return ex.feed_override * 1000;}
+void set_feed_override(uint16_t value) {ex.feed_override = value / 1000.0;}
 
 
 // Command callbacks
@@ -185,7 +273,4 @@ void command_set_axis_exec(void *data) {
   // Update motors
   int motor = axis_get_motor(cmd->axis);
   if (0 <= motor) motor_set_position(motor, cmd->position);
-
-  // Report
-  report_request();
 }
index 6dfb930a5d879231c5cea23195873d50b7da11f1..d139c361c35fe2837b1687365f482f1b4cd5dff9 100644 (file)
@@ -50,5 +50,7 @@ void exec_set_jerk(float j);
 
 void exec_set_cb(exec_cb_t cb);
 
-void exec_move_to_target(float time, const float target[]);
+void exec_move_to_target(const float target[]);
+stat_t exec_segment(float time, const float target[], float vel, float accel,
+                    float maxVel, float maxAccel, float maxJerk);
 stat_t exec_next();
diff --git a/src/avr/src/huanyang.c b/src/avr/src/huanyang.c
new file mode 100644 (file)
index 0000000..e5e4619
--- /dev/null
@@ -0,0 +1,303 @@
+/******************************************************************************\
+
+                 This file is part of the Buildbotics firmware.
+
+                   Copyright (c) 2015 - 2018, Buildbotics LLC
+                              All rights reserved.
+
+      This file ("the software") is free software: you can redistribute it
+      and/or modify it under the terms of the GNU General Public License,
+       version 2 as published by the Free Software Foundation. You should
+       have received a copy of the GNU General Public License, version 2
+      along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+      The software is distributed in the hope that it will be useful, but
+           WITHOUT ANY WARRANTY; without even the implied warranty of
+       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+                Lesser General Public License for more details.
+
+        You should have received a copy of the GNU Lesser General Public
+                 License along with the software.  If not, see
+                        <http://www.gnu.org/licenses/>.
+
+                 For information regarding this software email:
+                   "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#include "huanyang.h"
+#include "config.h"
+#include "modbus.h"
+
+#include <string.h>
+#include <math.h>
+
+
+/*
+  Huanyang is not quite Modbus compliant.
+
+  Message format is:
+
+    [id][func][length][data][checksum]
+
+  Where:
+
+     id       - 1-byte Peer ID
+     func     - 1-byte One of hy_func_t
+     length   - 1-byte Length data in bytes
+     data     - length bytes - Command arguments
+     checksum - 16-bit CRC: x^16 + x^15 + x^2 + 1 (0xa001) initial: 0xffff
+*/
+
+
+// See VFD manual pg56 3.1.3
+typedef enum {
+  HUANYANG_FUNC_READ = 1, // [len=1][hy_addr_t]
+  HUANYANG_FUNC_WRITE,    // [len=3][hy_addr_t][data]
+  HUANYANG_CTRL_WRITE,    // [len=1][hy_ctrl_state_t]
+  HUANYANG_CTRL_READ,     // [len=1][hy_ctrl_addr_t]
+  HUANYANG_FREQ_WRITE,    // [len=2][freq]
+  HUANYANG_RESERVED_1,
+  HUANYANG_RESERVED_2,
+  HUANYANG_LOOP_TEST,
+} hy_func_t;
+
+
+// Sent in HUANYANG_CTRL_WRITE
+// See VFD manual pg57 3.1.3.c
+typedef enum {
+  HUANYANG_RUN         = 1 << 0,
+  HUANYANG_FORWARD     = 1 << 1,
+  HUANYANG_REVERSE     = 1 << 2,
+  HUANYANG_STOP        = 1 << 3,
+  HUANYANG_REV_FWD     = 1 << 4,
+  HUANYANG_JOG         = 1 << 5,
+  HUANYANG_JOG_FORWARD = 1 << 6,
+  HUANYANG_JOG_REVERSE = 1 << 7,
+} hy_ctrl_state_t;
+
+
+// Returned by HUANYANG_CTRL_WRITE
+// See VFD manual pg57 3.1.3.c
+typedef enum {
+  HUANYANG_STATUS_RUN         = 1 << 0,
+  HUANYANG_STATUS_JOG         = 1 << 1,
+  HUANYANG_STATUS_COMMAND_REV = 1 << 2,
+  HUANYANG_STATUS_RUNNING     = 1 << 3,
+  HUANYANG_STATUS_JOGGING     = 1 << 4,
+  HUANYANG_STATUS_JOGGING_REV = 1 << 5,
+  HUANYANG_STATUS_BRAKING     = 1 << 6,
+  HUANYANG_STATUS_TRACK_START = 1 << 7,
+} hy_ctrl_status_t;
+
+
+// Sent in HUANYANG_CTRL_READ
+// See VFD manual pg57 3.1.3.d
+typedef enum {
+  HUANYANG_TARGET_FREQ,
+  HUANYANG_ACTUAL_FREQ,
+  HUANYANG_ACTUAL_CURRENT,
+  HUANYANG_ACTUAL_RPM,
+  HUANYANG_DCV,
+  HUANYANG_ACV,
+  HUANYANG_COUNTER,
+  HUANYANG_TEMPERATURE,
+} hy_ctrl_addr_t;
+
+
+static struct {
+  uint8_t state;
+
+  deinit_cb_t deinit_cb;
+  bool shutdown;
+  bool changed;
+  float speed;
+
+  float actual_freq;
+  float actual_current;
+  uint16_t actual_rpm;
+  uint16_t temperature;
+
+  float max_freq;
+  float min_freq;
+  uint16_t rated_rpm;
+
+  uint8_t status;
+} hy;
+
+
+static void _func_read_response(hy_addr_t addr, uint16_t value) {
+  switch (addr) {
+  case HY_PD005_MAX_FREQUENCY:         hy.max_freq  = value * 0.01; break;
+  case HY_PD011_FREQUENCY_LOWER_LIMIT: hy.min_freq  = value * 0.01; break;
+  case HY_PD144_RATED_MOTOR_RPM:       hy.rated_rpm = value;        break;
+  default: break;
+  }
+}
+
+
+static void _ctrl_read_response(hy_ctrl_addr_t addr, uint16_t value) {
+  switch (addr) {
+  case HUANYANG_ACTUAL_FREQ:    hy.actual_freq    = value * 0.01; break;
+  case HUANYANG_ACTUAL_CURRENT: hy.actual_current = value * 0.01; break;
+  case HUANYANG_ACTUAL_RPM:     hy.actual_rpm     = value;        break;
+  case HUANYANG_TEMPERATURE:    hy.temperature    = value;        break;
+  default: break;
+  }
+}
+
+
+static uint16_t _read_word(const uint8_t *data) {
+  return (uint16_t)data[0] << 8 | data[1];
+}
+
+
+static void _handle_response(hy_func_t func, const uint8_t *data) {
+  switch (func) {
+  case HUANYANG_FUNC_READ:
+    _func_read_response((hy_addr_t)*data, _read_word(data + 1));
+    break;
+
+  case HUANYANG_FUNC_WRITE: break;
+  case HUANYANG_CTRL_WRITE: hy.status = *data; break;
+
+  case HUANYANG_CTRL_READ:
+    _ctrl_read_response((hy_ctrl_addr_t)*data, _read_word(data + 1));
+    break;
+
+  case HUANYANG_FREQ_WRITE: break;
+  default: break;
+  }
+}
+
+
+static void _next_command();
+
+
+static bool _shutdown() {
+  if (!hy.shutdown) return false;
+  modbus_deinit();
+  if (hy.deinit_cb) hy.deinit_cb();
+  return true;
+}
+
+
+static void _modbus_cb(uint8_t func, uint8_t bytes, const uint8_t *data) {
+  if (!data) { // Modbus command failed
+    if (_shutdown()) return;
+    hy.state = 0;
+
+  } else if (bytes == *data + 1) {
+    _handle_response((hy_func_t)func, data + 1);
+
+    if (func == HUANYANG_CTRL_WRITE && _shutdown()) return;
+
+    // Next command
+    if (++hy.state == 9) {
+      if (hy.shutdown || hy.changed) hy.state = 0;
+      else hy.state = 5;
+      hy.changed = false;
+    }
+ }
+
+  _next_command();
+}
+
+
+static void _func_read(hy_addr_t addr) {
+  uint8_t data[2] = {1, addr};
+  modbus_func(HUANYANG_FUNC_READ, 2, data, 4, _modbus_cb);
+}
+
+
+static void _ctrl_write(hy_ctrl_state_t state) {
+  uint8_t data[2] = {1, state};
+  modbus_func(HUANYANG_CTRL_WRITE, 2, data, 2, _modbus_cb);
+}
+
+
+static void _ctrl_read(hy_ctrl_addr_t addr) {
+  uint8_t data[2] = {1, addr};
+  modbus_func(HUANYANG_CTRL_READ, 2, data, 4, _modbus_cb);
+}
+
+
+static void _freq_write(uint16_t freq) {
+  uint8_t data[3] = {2, (uint8_t)(freq >> 8), (uint8_t)freq};
+  modbus_func(HUANYANG_FREQ_WRITE, 3, data, 3, _modbus_cb);
+}
+
+
+static void _next_command() {
+  switch (hy.state) {
+  case 0: { // Update direction
+    hy_ctrl_state_t state = HUANYANG_STOP;
+    if (!hy.shutdown) {
+      if (0 < hy.speed)
+        state = (hy_ctrl_state_t)(HUANYANG_RUN | HUANYANG_FORWARD);
+      else if (hy.speed < 0)
+        state = (hy_ctrl_state_t)(HUANYANG_RUN | HUANYANG_REV_FWD);
+    }
+
+    _ctrl_write(state);
+    break;
+  }
+
+  case 1: _func_read(HY_PD005_MAX_FREQUENCY); break;
+  case 2: _func_read(HY_PD011_FREQUENCY_LOWER_LIMIT); break;
+  case 3: _func_read(HY_PD144_RATED_MOTOR_RPM); break;
+
+  case 4: { // Update freqency
+    // Compute frequency in Hz
+    float freq = fabs(hy.speed * hy.max_freq);
+
+    // Frequency write command
+    _freq_write(freq * 100);
+    break;
+  }
+
+  case 5: _ctrl_read(HUANYANG_ACTUAL_FREQ);    break;
+  case 6: _ctrl_read(HUANYANG_ACTUAL_CURRENT); break;
+  case 7: _ctrl_read(HUANYANG_ACTUAL_RPM);     break;
+  case 8: _ctrl_read(HUANYANG_TEMPERATURE);    break;
+  }
+}
+
+
+void huanyang_init() {
+  modbus_init();
+  memset(&hy, 0, sizeof(hy));
+  _next_command();
+}
+
+
+void huanyang_deinit(deinit_cb_t cb) {
+  hy.deinit_cb = cb;
+  hy.shutdown = true;
+}
+
+
+void huanyang_set(float speed) {
+  if (hy.speed != speed && !hy.shutdown) {
+    hy.speed = speed;
+    hy.changed = true;
+  }
+}
+
+
+float huanyang_get() {return hy.actual_freq / hy.max_freq;}
+
+
+void huanyang_stop() {
+  huanyang_set(0);
+  hy.shutdown = true;
+}
+
+
+float get_hy_freq() {return hy.actual_freq;}
+float get_hy_current() {return hy.actual_current;}
+uint16_t get_hy_temp() {return hy.temperature;}
+float get_hy_max_freq() {return hy.max_freq;}
+float get_hy_min_freq() {return hy.min_freq;}
+uint16_t get_hy_rated_rpm() {return hy.rated_rpm;}
+float get_hy_status() {return hy.status;}
diff --git a/src/avr/src/huanyang.h b/src/avr/src/huanyang.h
new file mode 100644 (file)
index 0000000..2a05c8b
--- /dev/null
@@ -0,0 +1,226 @@
+/******************************************************************************\
+
+                 This file is part of the Buildbotics firmware.
+
+                   Copyright (c) 2015 - 2018, Buildbotics LLC
+                              All rights reserved.
+
+      This file ("the software") is free software: you can redistribute it
+      and/or modify it under the terms of the GNU General Public License,
+       version 2 as published by the Free Software Foundation. You should
+       have received a copy of the GNU General Public License, version 2
+      along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+      The software is distributed in the hope that it will be useful, but
+           WITHOUT ANY WARRANTY; without even the implied warranty of
+       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+                Lesser General Public License for more details.
+
+        You should have received a copy of the GNU Lesser General Public
+                 License along with the software.  If not, see
+                        <http://www.gnu.org/licenses/>.
+
+                 For information regarding this software email:
+                   "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#pragma once
+
+#include "spindle.h"
+
+
+void huanyang_init();
+void huanyang_deinit(deinit_cb_t cb);
+void huanyang_set(float speed);
+float huanyang_get();
+void huanyang_stop();
+
+
+/// See Huanyang VFD user manual
+typedef enum {
+  HY_PD000_PARAMETER_LOCK,
+  HY_PD001_SOURCE_OF_OPERATION_COMMANDS,
+  HY_PD002_SOURCE_OF_OPERATING_FREQUENCY,
+  HY_PD003_MAIN_FREQUENCY,
+  HY_PD004_BASE_FREQUENCY,
+  HY_PD005_MAX_FREQUENCY,
+  HY_PD006_INTERMEDIATE_FREQUENCY,
+  HY_PD007_MIN_FREQUENCY,
+  HY_PD008_MAX_VOLTAGE,
+  HY_PD009_INTERMEDIATE_VOLTAGE,
+  HY_PD010_MIN_VOLTAGE,
+  HY_PD011_FREQUENCY_LOWER_LIMIT,
+  HY_PD012_RESERVED,
+  HY_PD013_PARAMETER_RESET,
+  HY_PD014_ACCEL_TIME_1,
+  HY_PD015_DECEL_TIME_1,
+  HY_PD016_ACCEL_TIME_2,
+  HY_PD017_DECEL_TIME_2,
+  HY_PD018_ACCEL_TIME_3,
+  HY_PD019_DECEL_TIME_3,
+  HY_PD020_ACCEL_TIME_4,
+  HY_PD021_DECEL_TIME_4,
+  HY_PD022_FACTORY_RESERVED,
+  HY_PD023_REV_ROTATION_SELECT,
+  HY_PD024_STOP_KEY,
+  HY_PD025_STARTING_MODE,
+  HY_PD026_STOPPING_MODE,
+  HY_PD027_STARTING_FREQUENCY,
+  HY_PD028_STOPPING_FREQUENCY,
+  HY_PD029_DC_BRAKING_TIME_AT_START,
+  HY_PD030_DC_BRAKING_TIME_AT_STOP,
+  HY_PD031_DC_BRAKING_VOLTAGE_LEVEL,
+  HY_PD032_FREQUENCY_TRACK_TIME,
+  HY_PD033_CURRENT_LEVEL_FOR_FREQUENCY_TRACK,
+  HY_PD034_VOLTAGE_RISE_TIME_FOR_FREQUENCY_TRACK,
+  HY_PD035_FREQUENCY_STEP_LENGTH,
+  HY_PD036,
+  HY_PD037,
+  HY_PD038,
+  HY_PD039,
+  HY_PD040,
+  HY_PD041_CARRIER_FREQUENCY,
+  HY_PD042_JOGGING_FREQUENCY,
+  HY_PD043_S_CURVE_TIME,
+  HY_PD044_MULTI_INPUT_FOR,
+  HY_PD045_MULTI_INPUT_REV,
+  HY_PD046_MULTI_INPUT_RST,
+  HY_PD047_MULTI_INPUT_SPH,
+  HY_PD048_MULTI_INPUT_SPM,
+  HY_PD049_MULTI_INPUT_SPL,
+  HY_PD050_MULTI_OUTPUT_DRV,
+  HY_PD051_MULTI_OUTPUT_UPF,
+  HY_PD052_MULTI_OUTPUT_FA_FB_FC,
+  HY_PD053_MULTI_OUTPUT_KA_KB,
+  HY_PD054_MULTI_OUTPUT_AM,
+  HY_PD055_AM_ANALOG_OUTPUT_GAIN,
+  HY_PD056_SKIP_FREQUENCY_1,
+  HY_PD057_SKIP_FREQUENCY_2,
+  HY_PD058_SKIP_FREQUENCY_3,
+  HY_PD059_SKIP_FREQUENCY_RANGE,
+  HY_PD060_UNIFORM_FREQUENCY_1,
+  HY_PD061_UNIFORM_FREQUENCY_2,
+  HY_PD062_UNIFORM_FREQUENCY_RANGE,
+  HY_PD063_TIMER_1_TIME,
+  HY_PD064_TIMER_2_TIME,
+  HY_PD065_COUNTING_VALUE,
+  HY_PD066_INTERMEDIATE_COUNTER,
+  HY_PD067,
+  HY_PD068,
+  HY_PD069,
+  HY_PD070_ANALOG_INPUT,
+  HY_PD071_ANALOG_FILTERING_CONSTANT,
+  HY_PD072_HIGHER_ANALOG_FREQUENCY,
+  HY_PD073_LOWER_ANALOG_FREQUENCY,
+  HY_PD074_BIAS_DIRECTION_AT_HIGHER_FREQUENCY,
+  HY_PD075_BIAS_DIRECTION_AT_LOWER_FREQUENCY,
+  HY_PD076_ANALOG_NEGATIVE_BIAS_REVERSE,
+  HY_PD077_UP_DOWN_FUNCTION,
+  HY_PD078_UP_DOWN_SPEED,
+  HY_PD079,
+  HY_PD080_PLC_OPERATION,
+  HY_PD081_AUTO_PLC,
+  HY_PD082_PLC_RUNNING_DIRECTION,
+  HY_PD083,
+  HY_PD084_PLC_RAMP_TIME,
+  HY_PD085,
+  HY_PD086_FREQUENCY_2,
+  HY_PD087_FREQUENCY_3,
+  HY_PD088_FREQUENCY_4,
+  HY_PD089_FREQUENCY_5,
+  HY_PD090_FREQUENCY_6,
+  HY_PD091_FREQUENCY_7,
+  HY_PD092_FREQUENCY_8,
+  HY_PD093,
+  HY_PD094,
+  HY_PD095,
+  HY_PD096,
+  HY_PD097,
+  HY_PD098,
+  HY_PD099,
+  HY_PD100,
+  HY_PD101_TIMER_1,
+  HY_PD102_TIMER_2,
+  HY_PD103_TIMER_3,
+  HY_PD104_TIMER_4,
+  HY_PD105_TIMER_5,
+  HY_PD106_TIMER_6,
+  HY_PD107_TIMER_7,
+  HY_PD108_TIMER_8,
+  HY_PD109,
+  HY_PD110,
+  HY_PD111,
+  HY_PD112,
+  HY_PD113,
+  HY_PD114,
+  HY_PD115,
+  HY_PD116,
+  HY_PD117_AUTOPLC_MEMORY_FUNCTION,
+  HY_PD118_OVER_VOLTAGE_STALL_PREVENTION,
+  HY_PD119_STALL_PREVENTION_LEVEL_AT_RAMP_UP,
+  HY_PD120_STALL_PREVENTION_LEVEL_AT_CONSTANT_SPEED,
+  HY_PD121_DECEL_TIME_FOR_STALL_PREVENTION_AT_CONSTANT_SPEED,
+  HY_PD122_STALL_PREVENTION_LEVEL_AT_DECELERATION,
+  HY_PD123_OVER_TORQUE_DETECT_MODE,
+  HY_PD124_OVER_TORQUE_DETECT_LEVEL,
+  HY_PD125_OVER_TORQUE_DETECT_TIME,
+  HY_PD126,
+  HY_PD127,
+  HY_PD128,
+  HY_PD129,
+  HY_PD130_NUMBER_OF_AUXILIARY_PUMP,
+  HY_PD131_CONTINUOUS_RUNNING_TIME_OF_AUXILIARY_PUMPS,
+  HY_PD132_INTERLOCKING_TIME_OF_AUXILIARY_PUMP,
+  HY_PD133_HIGH_SPEED_RUNNING_TIME,
+  HY_PD134_LOW_SPEED_RUNNING_TIME,
+  HY_PD135_STOPPING_VOLTAGE_LEVEL,
+  HY_PD136_LASTING_TIME_OF_STOPPING_VOLTAGE_LEVEL,
+  HY_PD137_WAKEUP_VOLTAGE_LEVEL,
+  HY_PD138_SLEEP_FREQUENCY,
+  HY_PD139_LASTING_TIME_OF_SLEEP_FREQUENCY,
+  HY_PD140,
+  HY_PD141_RATED_MOTOR_VOLTAGE,
+  HY_PD142_RATED_MOTOR_CURRENT,
+  HY_PD143_MOTOR_POLE_NUMBER,
+  HY_PD144_RATED_MOTOR_RPM,
+  HY_PD145_AUTO_TORQUE_COMPENSATION,
+  HY_PD146_MOTOR_NO_LOAD_CURRENT,
+  HY_PD147_MOTOR_SLIP_COMPENSATION,
+  HY_PD148,
+  HY_PD149,
+  HY_PD150_AUTO_VOLTAGE_REGULATION,
+  HY_PD151_AUTO_ENERGY_SAVING,
+  HY_PD152_FAULT_RESTART_TIME,
+  HY_PD153_RESTART_AFTER_INSTANTANEOUS_STOP,
+  HY_PD154_ALLOWABLE_POWER_BREAKDOWN_TIME,
+  HY_PD155_NUMBER_OF_ABNORMAL_RESTART,
+  HY_PD156_PROPORTIONAL_CONSTANT,
+  HY_PD157_INTEGRAL_TIME,
+  HY_PD158_DIFFERENTIAL_TIME,
+  HY_PD159_TARGET_VALUE,
+  HY_PD160_PID_TARGET_VALUE,
+  HY_PD161_PID_UPPER_LIMIT,
+  HY_PD162_PID_LOWER_LIMIT,
+  HY_PD163_COMMUNICATION_ADDRESSES,
+  HY_PD164_COMMUNICATION_BAUD_RATE,
+  HY_PD165_COMMUNICATION_DATA_METHOD,
+  HY_PD166,
+  HY_PD167,
+  HY_PD168,
+  HY_PD169,
+  HY_PD170_DISPLAY_ITEMS,
+  HY_PD171_DISPLAY_ITEMS_OPEN,
+  HY_PD172_FAULT_CLEAR,
+  HY_PD173,
+  HY_PD174_RATED_CURRENT_OF_INVERTER,
+  HY_PD175_INVERTER_MODEL,
+  HY_PD176_INVERTER_FREQUENCY_STANDARD,
+  HY_PD177_FAULT_RECORD_1,
+  HY_PD178_FAULT_RECORD_2,
+  HY_PD179_FAULT_RECORD_3,
+  HY_PD180_FAULT_RECORD_4,
+  HY_PD181_SOFTWARE_VERSION,
+  HY_PD182_MANUFACTURE_DATE,
+  HY_PD183_SERIAL_NO,
+} hy_addr_t;
index adec1ac5aa6807a2d1b6eaa713041875cfc59b20..a8ba510e433b860bd8178dc5e39f5c03da87f2ed 100644 (file)
@@ -109,7 +109,7 @@ stat_t jog_exec() {
 
   // Set velocity and target
   exec_set_velocity(sqrt(velocity_sqr));
-  exec_move_to_target(SEGMENT_TIME, target);
+  exec_move_to_target(target);
 
   return STAT_OK;
 }
index 9ecd62387eb9079fc5d41ea46f09016edd086dff..fbd0d9b78c78c9acc83087ff22f1d32b91e12d0c 100644 (file)
 #include "exec.h"
 #include "axis.h"
 #include "command.h"
-#include "state.h"
-#include "seek.h"
 #include "util.h"
 #include "SCurve.h"
 
 #include <math.h>
+#include <float.h>
 #include <string.h>
-#include <stdio.h>
 
 
 typedef struct {
@@ -44,6 +42,7 @@ typedef struct {
   float target[AXES];
   float times[7];
   float target_vel;
+  float max_vel;
   float max_accel;
   float max_jerk;
 
@@ -53,25 +52,22 @@ typedef struct {
 
 
 static struct {
-  float current_time;
+  line_t line;
+
   int section;
-  bool stop_section;
-  float offset_time;
   int seg;
 
-  line_t line;
-
   float iD; // Initial section distance
   float iV; // Initial section velocity
   float iA; // Initial section acceleration
   float jerk;
-  float dist;
-} l = {.current_time = SEGMENT_TIME};
+  float lV; // Last velocity
+} l;
 
 
 static void _segment_target(float target[AXES], float d) {
-  for (int i = 0; i < AXES; i++)
-    target[i] = l.line.start[i] + l.line.unit[i] * d;
+  for (int axis = 0; axis < AXES; axis++)
+    target[axis] = l.line.start[axis] + l.line.unit[axis] * d;
 }
 
 
@@ -92,16 +88,7 @@ static float _segment_accel(float t) {
 
 static bool _section_next() {
   while (++l.section < 7) {
-    float section_time = l.line.times[l.section];
-    if (!section_time) continue;
-
-    // Check if last section
-    bool last_section = true;
-    for (int i = l.section + 1; i < 7; i++)
-      if (l.line.times[i]) last_section = false;
-
-    // Check if stop section
-    l.stop_section = last_section && !l.line.target_vel;
+    if (!l.line.times[l.section]) continue;
 
     // Jerk
     switch (l.section) {
@@ -117,19 +104,6 @@ static bool _section_next() {
     case 5: case 6: l.iA = -l.line.max_jerk * l.line.times[4]; break;
     default: l.iA = 0;
     }
-    exec_set_acceleration(l.iA);
-
-    // Skip sections which do not land on a SEGMENT_TIME
-    if (section_time < l.current_time && !l.stop_section) {
-      l.current_time -= l.line.times[l.section];
-      l.iD = _segment_distance(section_time);
-      l.iV = _segment_velocity(section_time);
-      continue;
-    }
-
-    // Setup section time offset and segment counter
-    l.offset_time = l.current_time;
-    l.seg = 0;
 
     return true;
   }
@@ -138,138 +112,51 @@ static bool _section_next() {
 }
 
 
-static void _done() {
-  seek_end();
-  exec_set_cb(0);
-}
-
-
-static void _move(float t, float target[AXES], float v, float a) {
-  exec_set_velocity(v);
-  exec_set_acceleration(a);
-
-  if (seek_switch_found()) state_seek_hold();
-
-  exec_move_to_target(t, target);
-}
-
-
-static stat_t _pause() {
-  float t = SEGMENT_TIME - l.current_time;
-  float v = exec_get_velocity();
-  float a = exec_get_acceleration();
-  float j = l.line.max_jerk;
-
-  if (v < MIN_VELOCITY) {
-    command_reset_position();
-    exec_set_velocity(0);
-    exec_set_acceleration(0);
-    exec_set_jerk(0);
-    state_holding();
-    _done();
-
-    return STAT_NOP;
-  }
-
-  // Compute new velocity, acceleration and travel distance
-  a = SCurve::nextAccel(t, 0, v, a, l.line.max_accel, j);
-  v += a * t;
-  l.dist += v * t;
-
-  // Target end of line exactly if we are close
-  if (l.dist - 0.001 < l.line.length && l.line.length < l.dist + 0.001)
-    l.dist = l.line.length;
-
-  if (l.line.length < l.dist) {
-    // Compute time left in current section
-    l.current_time = t - (l.dist - l.line.length) / v;
-    _done();
-
-    return STAT_AGAIN;
-  }
-
-  // Compute target position from distance
-  float target[AXES];
-  _segment_target(target, l.dist);
-
-  l.current_time = 0;
-
-  // Compute jerk
-  float oldAccel = exec_get_acceleration();
-  exec_set_jerk(oldAccel == a ? 0 : (oldAccel < a ? j : -j));
-
-  _move(SEGMENT_TIME, target, v, a);
-  return STAT_OK;
-}
-
-
 static stat_t _line_exec() {
-  // Pause if requested.
-  if (state_get() == STATE_STOPPING) {
-    if (SEGMENT_TIME < l.current_time) l.current_time = 0;
-    exec_set_cb(_pause);
-    return _pause();
-  }
-
+  // Compute times
   float section_time = l.line.times[l.section];
-
-  // Adjust segment time if near a stopping point
   float seg_time = SEGMENT_TIME;
-  if (l.stop_section && section_time - l.current_time < SEGMENT_TIME) {
-    // TODO Instead of adjusting seg_time either absorb the next partial segment
-    // or expand it to a full segment so that we only have SEGMENT_TIME length
-    // segments.
-    seg_time += section_time - l.current_time;
-    l.offset_time += section_time - l.current_time;
-    l.current_time = section_time;
-  }
-
-  // Compute distance and velocity.  Must be computed before advancing time.
-  float d = _segment_distance(l.current_time);
-  float v = _segment_velocity(l.current_time);
-  float a = _segment_accel(l.current_time);
-
-  // Advance time.  This is the start time for the next segment.
-  l.current_time = l.offset_time + ++l.seg * SEGMENT_TIME;
+  float t = ++l.seg * SEGMENT_TIME;
 
-  // Check if section complete
-  bool lastSection = false;
-  if (section_time < l.current_time) {
-    l.current_time -= section_time;
-    l.iD = _segment_distance(section_time);
-    l.iV = _segment_velocity(section_time);
-
-    // Next section
-    lastSection = !_section_next();
+  // Don't exceed section time
+  if (section_time < t) {
+    seg_time = section_time - (l.seg - 1) * SEGMENT_TIME;
+    t = section_time;
   }
 
-  // Do move & update exec
-  if (lastSection && l.stop_section)
-    // Stop exactly on target to correct for floating-point errors
-    _move(seg_time, l.line.target, 0, 0);
-
-  else {
-    // Compute target position from distance
-    float target[AXES];
-    _segment_target(target, d);
+  // Compute distance and velocity
+  float d = _segment_distance(t);
+  float v = _segment_velocity(t);
+  float a = _segment_accel(t);
 
-    _move(seg_time, target, v, a);
-    l.dist = d;
-  }
+  // Don't allow overshoot
+  if (l.line.length < d) d = l.line.length;
 
-  // Release exec if we are done
-  if (lastSection) {
-    exec_set_velocity(l.line.target_vel);
-    _done();
+  // Check if section complete
+  if (t == section_time) {
+    if (_section_next()) {
+      // Setup next section
+      l.seg = 0;
+      l.iD = d;
+      l.iV = v;
+
+    } else {
+      exec_set_cb(0);
+
+      // Last segment of last section
+      // Use exact target values to correct for floating-point errors
+      return exec_segment(seg_time, l.line.target, l.line.target_vel, a,
+                          l.line.max_vel, l.line.max_accel, l.line.max_jerk);
+    }
   }
 
-  return STAT_OK;
-}
-
+  // Compute target position from distance
+  float target[AXES];
+  _segment_target(target, d);
 
-void _print_vector(const char *name, float v[4]) {
-  printf_P(PSTR("%s %f %f %f %f\n"),
-           name, (double)v[0], (double)v[1], (double)v[2], (double)v[3]);
+  // Segment move
+  return exec_segment
+    (seg_time, target, v, a, l.line.max_vel, l.line.max_accel, l.line.max_jerk);
 }
 
 
@@ -322,16 +209,22 @@ stat_t command_line(char *cmd) {
   command_set_position(line.target);
 
   // Compute direction vector
-  for (int i = 0; i < AXES; i++)
-    if (axis_is_enabled(i)) {
-      line.unit[i] = line.target[i] - line.start[i];
-      line.length += line.unit[i] * line.unit[i];
-
-    } else line.unit[i] = 0;
+  for (int axis = 0; axis < AXES; axis++) {
+    line.unit[axis] = line.target[axis] - line.start[axis];
+    line.length += line.unit[axis] * line.unit[axis];
+  }
 
   line.length = sqrt(line.length);
-  for (int i = 0; i < AXES; i++)
-    if (line.unit[i]) line.unit[i] /= line.length;
+  for (int axis = 0; axis < AXES; axis++)
+    if (line.unit[axis]) line.unit[axis] /= line.length;
+
+  // Compute max velocity
+  line.max_vel = FLT_MAX;
+  for (int axis = 0; axis < AXES; axis++)
+    if (line.unit[axis]) {
+      float axis_max_vel = axis_get_velocity_max(axis) / fabs(line.unit[axis]);
+      if (axis_max_vel < line.max_vel) line.max_vel = axis_max_vel;
+    }
 
   // Queue
   command_push(COMMAND_line, &line);
@@ -346,9 +239,12 @@ unsigned command_line_size() {return sizeof(line_t);}
 void command_line_exec(void *data) {
   l.line = *(line_t *)data;
 
-  // Init dist & velocity
-  l.iD = l.dist = 0;
-  l.iV = exec_get_velocity();
+  // Setup first section
+  l.seg = 0;
+  l.iD = 0;
+  // If current velocity is non-zero use last target velocity
+  l.iV = exec_get_velocity() ? l.lV : 0;
+  l.lV = l.line.target_vel;
 
   // Find first section
   l.section = -1;
index ca8bd0525a673110128ae723bb7b10b74b1f2ff0..f879e652268291600f443eb7afc496378d4e0d72 100644 (file)
 STAT_MSG(OK,                    "OK")
 STAT_MSG(AGAIN,                 "Run command again")
 STAT_MSG(NOP,                   "No op")
-STAT_MSG(PAUSE,                 "Pause")
 STAT_MSG(INTERNAL_ERROR,        "Internal error")
 STAT_MSG(ESTOP_USER,            "User triggered EStop")
 STAT_MSG(ESTOP_SWITCH,          "Switch triggered EStop")
 STAT_MSG(UNRECOGNIZED_NAME,     "Unrecognized command or variable name")
 STAT_MSG(INVALID_COMMAND,       "Invalid command")
-STAT_MSG(INVALID_ARGUMENTS,     "Invalid argument(s) to command")
-STAT_MSG(TOO_MANY_ARGUMENTS,    "Too many arguments to command")
-STAT_MSG(TOO_FEW_ARGUMENTS,     "Too few arguments to command")
-STAT_MSG(COMMAND_NOT_ACCEPTED,  "Command not accepted at this time")
+STAT_MSG(INVALID_ARGUMENTS,     "Invalid arguments")
+STAT_MSG(TOO_MANY_ARGUMENTS,    "Too many arguments")
+STAT_MSG(TOO_FEW_ARGUMENTS,     "Too few arguments")
 STAT_MSG(MACHINE_ALARMED,       "Machine alarmed - Command not processed")
-STAT_MSG(EXPECTED_MOVE,         "A move was expected but none was queued")
-STAT_MSG(QUEUE_FULL,            "Queue full")
-STAT_MSG(QUEUE_EMPTY,           "Queue empty")
+STAT_MSG(EXPECTED_MOVE,         "A move expected but none queued")
 STAT_MSG(BAD_FLOAT,             "Failed to parse float")
-STAT_MSG(INVALID_VARIABLE,      "Invalid variable")
+STAT_MSG(BAD_INT,               "Failed to parse integer")
 STAT_MSG(INVALID_VALUE,         "Invalid value")
+STAT_MSG(INVALID_TYPE,          "Invalid type")
 STAT_MSG(READ_ONLY,             "Variable is read only")
-STAT_MSG(BUFFER_OVERFLOW,       "Buffer overflow")
 STAT_MSG(ALL_ZERO_SCURVE_TIMES, "All zero s-curve times")
 STAT_MSG(NEGATIVE_SCURVE_TIME,  "Negative s-curve time")
 STAT_MSG(SEEK_NOT_ENABLED,      "Switch not enabled")
index 99217707a7e301b66b92f231f45fc27d59088993..be3840053d1dd3958c7ae91332d0671299e9da0a 100644 (file)
 #include <stdio.h>
 
 
+typedef enum {
+  MODBUS_DISCONNECTED,
+  MODBUS_OK,
+  MODBUS_CRC,
+  MODBUS_INVALID,
+  MODBUS_TIMEDOUT,
+} modbus_status_t;
+
+
 static struct {
   bool debug;
   uint8_t id;
   baud_t baud;
   parity_t parity;
-  stop_t stop;
+} cfg = {false, 1, USART_BAUD_9600, USART_NONE};
+
 
+static struct {
   uint8_t bytes;
   uint8_t command[MODBUS_BUF_SIZE];
   uint8_t command_length;
   uint8_t response[MODBUS_BUF_SIZE];
   uint8_t response_length;
 
-  modbus_cb_t receive_cb;
-
   uint16_t addr;
-  modbus_read_cb_t read_cb;
-  modbus_write_cb_t write_cb;
+  modbus_rw_cb_t rw_cb;
+  modbus_cb_t receive_cb;
 
-  uint32_t last;
+  uint32_t last_write;
+  uint32_t last_read;
   uint8_t retry;
-  bool connected;
+  uint8_t status;
+  bool write_ready;
   bool busy;
-} mb = {false, 1, USART_BAUD_9600, USART_NONE, USART_1STOP};
+} state = {0};
 
 
 static uint16_t _crc16(const uint8_t *buffer, unsigned length) {
@@ -104,35 +115,49 @@ static void _set_rxc_interrupt(bool enable) {
 }
 
 
+static void _write_word(uint8_t *dst, uint16_t value, bool little_endian) {
+  dst[!little_endian]  = value;
+  dst[little_endian] = value >> 8;
+}
+
+
+static uint16_t _read_word(const uint8_t *data, bool little_endian) {
+  return (uint16_t)data[little_endian] << 8 | data[!little_endian];
+}
+
+
 static bool _check_response() {
   // Check CRC
-  uint16_t computed = _crc16(mb.response, mb.response_length - 2);
-  uint16_t expected = (mb.response[mb.response_length - 1] << 8) |
-    mb.response[mb.response_length - 2];
+  uint16_t computed = _crc16(state.response, state.response_length - 2);
+  uint16_t expected =
+    _read_word(state.response + state.response_length - 2, true);
 
   if (computed != expected) {
-    char sent[mb.command_length * 2 + 1];
-    char response[mb.response_length * 2 + 1];
-    format_hex_buf(sent, mb.command, mb.command_length);
-    format_hex_buf(response, mb.response, mb.response_length);
+    char sent[state.command_length * 2 + 1];
+    char response[state.response_length * 2 + 1];
+    format_hex_buf(sent, state.command, state.command_length);
+    format_hex_buf(response, state.response, state.response_length);
 
-    STATUS_WARNING(STAT_OK, "modbus: invalid CRC, expected=0x%04x got=0x%04x "
-                   "sent=0x%s received=0x%s",
+    STATUS_WARNING(STAT_OK, "modbus: invalid CRC, received=0x%04x "
+                   "computed=0x%04x sent=0x%s received=0x%s",
                    expected, computed, sent, response);
+    state.status = MODBUS_CRC;
     return false;
   }
 
   // Check that slave id matches
-  if (mb.command[0] != mb.response[0]) {
+  if (state.command[0] != state.response[0]) {
     STATUS_WARNING(STAT_OK, "modbus: unexpected slave id, expected=%u got=%u",
-                   mb.command[0], mb.response[0]);
+                   state.command[0], state.response[0]);
+    state.status = MODBUS_INVALID;
     return false;
   }
 
   // Check that function code matches
-  if (mb.command[1] != mb.response[1]) {
+  if (state.command[1] != state.response[1]) {
     STATUS_WARNING(STAT_OK, "modbus: invalid function code, expected=%u got=%u",
-                   mb.command[1], mb.response[1]);
+                   state.command[1], state.response[1]);
+    state.status = MODBUS_INVALID;
     return false;
   }
 
@@ -140,27 +165,37 @@ static bool _check_response() {
 }
 
 
+static void _notify(uint8_t func, uint8_t bytes, const uint8_t *data) {
+  if (!state.receive_cb) return;
+
+  modbus_cb_t cb = state.receive_cb;
+  state.receive_cb = 0; // May be set in callback
+
+  cb(func, bytes, data);
+}
+
+
 static void _handle_response() {
   if (!_check_response()) return;
 
-  mb.last = 0;  // Clear timeout timer
-  mb.retry = 0; // Reset retry counter
-  mb.connected = true;
-  mb.busy = false;
+  state.last_write = 0;             // Clear timeout timer
+  state.last_read = rtc_get_time(); // Set delay timer
+  state.retry = 0;                  // Reset retry counter
+  state.status = MODBUS_OK;
+  state.busy = false;
 
-  if (mb.receive_cb)
-    mb.receive_cb(mb.response[1], mb.response_length - 4, mb.response + 2);
+  _notify(state.response[1], state.response_length - 4, state.response + 2);
 }
 
 
 /// Data register empty interrupt
 ISR(RS485_DRE_vect) {
-  RS485_PORT.DATA = mb.command[mb.bytes++];
+  RS485_PORT.DATA = state.command[state.bytes++];
 
-  if (mb.bytes == mb.command_length) {
+  if (state.bytes == state.command_length) {
     _set_dre_interrupt(false);
     _set_txc_interrupt(true);
-    mb.bytes = 0;
+    state.bytes = 0;
   }
 }
 
@@ -169,46 +204,43 @@ ISR(RS485_DRE_vect) {
 ISR(RS485_TXC_vect) {
   _set_txc_interrupt(false);
   _set_rxc_interrupt(true);
-  _set_write(false);        // Switch to read mode
-  mb.last = rtc_get_time(); // Set timeout timer
+  _set_write(false);              // Switch to read mode
+  state.last_write = rtc_get_time(); // Set timeout timer
 }
 
 
 /// Data received interrupt
 ISR(RS485_RXC_vect) {
-  mb.response[mb.bytes++] = RS485_PORT.DATA;
+  state.response[state.bytes++] = RS485_PORT.DATA;
 
-  if (mb.bytes == mb.response_length) {
+  if (state.bytes == state.response_length) {
     _set_rxc_interrupt(false);
     _set_write(true); // Back to write mode
-    mb.bytes = 0;
+    state.bytes = 0;
     _handle_response();
   }
 }
 
 
-void _read_cb(uint8_t func, uint8_t bytes, const uint8_t *data) {
+static void _read_cb(uint8_t func, uint8_t bytes, const uint8_t *data) {
   if (func == MODBUS_READ_OUTPUT_REG && bytes == 3 && data[0] == 2) {
-    uint16_t value = (uint16_t)data[1] << 8 | data[2];
-    if (mb.read_cb) mb.read_cb(true, mb.addr, value);
+    if (state.rw_cb) state.rw_cb(true, state.addr, _read_word(data, false));
     return;
   }
 
-  if (mb.read_cb) mb.read_cb(false, mb.addr, 0);
+  if (state.rw_cb) state.rw_cb(false, state.addr, 0);
 }
 
 
-void _write_cb(uint8_t func, uint8_t bytes, const uint8_t *data) {
-  if (func == MODBUS_WRITE_OUTPUT_REG && bytes == 4) {
-    uint16_t addr = (uint16_t)data[0] << 8 | data[1];
-
-    if (addr == mb.addr) {
-      if (mb.write_cb) mb.write_cb(true, mb.addr);
-      return;
-    }
+static void _write_cb(uint8_t func, uint8_t bytes, const uint8_t *data) {
+  if (func == MODBUS_WRITE_OUTPUT_REG && bytes == 4 &&
+      _read_word(data, false) == state.addr) {
+    if (state.rw_cb)
+      state.rw_cb(true, state.addr, _read_word(state.command + 4, false));
+    return;
   }
 
-  if (mb.write_cb) mb.write_cb(false, mb.addr);
+  if (state.rw_cb) state.rw_cb(false, state.addr, 0);
 }
 
 
@@ -223,29 +255,16 @@ static void _reset() {
   x = RS485_PORT.STATUS;
   x = x;
 
-  // Save settings
-  bool debug = mb.debug;
-  uint8_t id = mb.id;
-  baud_t baud = mb.baud;
-  parity_t parity = mb.parity;
-  stop_t stop = mb.stop;
-
   // Clear state
-  memset(&mb, 0, sizeof(mb));
-
-  // Restore settings
-  mb.debug = debug;
-  mb.id = id;
-  mb.baud = baud;
-  mb.parity = parity;
-  mb.stop = stop;
+  state.write_ready = false;
+  state.busy = false;
 }
 
 
 static void _retry() {
-  mb.last = 0;
-  mb.bytes = 0;
-  mb.retry++;
+  state.last_write = 0;
+  state.bytes = 0;
+  state.retry++;
 
   _set_write(true); // RS485 write mode
 
@@ -254,25 +273,29 @@ static void _retry() {
   _set_dre_interrupt(true);
 
   // Try changing pin polarity
-  if (mb.retry == MODBUS_RETRIES) {
+  if (state.retry == MODBUS_RETRIES) {
     PINCTRL_PIN(RS485_RO_PIN) ^= PORT_INVEN_bm;
     PINCTRL_PIN(RS485_DI_PIN) ^= PORT_INVEN_bm;
   }
 
-  if (mb.debug) STATUS_DEBUG("modbus: retry %d", mb.retry);
+  if (cfg.debug) STATUS_DEBUG("modbus: retry %d", state.retry);
 }
 
 
 static void _timeout() {
-  if (mb.debug) STATUS_DEBUG("modbus: timedout");
+  if (cfg.debug) STATUS_DEBUG("modbus: timedout");
 
-  modbus_cb_t cb = mb.receive_cb;
-  uint8_t func = mb.command[1];
+  if (state.status == MODBUS_OK || state.status == MODBUS_DISCONNECTED)
+    state.status = MODBUS_TIMEDOUT;
 
   _reset();
+  _notify(state.command[1], 0, 0);
+}
+
 
-  // Notify caller
-  if (cb) cb(func, 0, 0);
+static stop_t _get_stop() {
+  // RTU mode characters must always be 11-bits long
+  return cfg.parity == USART_NONE ? USART_2STOP : USART_1STOP;
 }
 
 
@@ -285,14 +308,18 @@ void modbus_init() {
   OUTSET_PIN(RS485_RW_PIN); // High
   DIRSET_PIN(RS485_RW_PIN); // Output
 
-  usart_init_port(&RS485_PORT, mb.baud, mb.parity, USART_8BITS, mb.stop);
-
   _reset();
+  memset(&state, 0, sizeof(state));
+  state.status = MODBUS_DISCONNECTED;
+
+  usart_init_port(&RS485_PORT, cfg.baud, cfg.parity, USART_8BITS, _get_stop());
 }
 
 
 void modbus_deinit() {
   _reset();
+  memset(&state, 0, sizeof(state));
+  state.status = MODBUS_DISCONNECTED;
 
   // Disable USART
   RS485_PORT.CTRLB &= ~(USART_RXEN_bm | USART_TXEN_bm);
@@ -303,99 +330,119 @@ void modbus_deinit() {
 }
 
 
-bool modbus_busy() {return mb.busy;}
+bool modbus_busy() {return state.busy;}
 
 
-void modbus_func(uint8_t func, uint8_t send, const uint8_t *data,
-                 uint8_t receive, modbus_cb_t receive_cb) {
-  ASSERT(send + 4 <= MODBUS_BUF_SIZE);
-  ASSERT(receive + 4 <= MODBUS_BUF_SIZE);
-
-  mb.command[0] = mb.id;
-  mb.command[1] = func;
-  memcpy(mb.command + 2, data, send);
-  uint16_t crc = _crc16(mb.command, send + 2);
-  mb.command[send + 2] = crc;
-  mb.command[send + 3] = crc >> 8;
-
-  mb.bytes = 0;
-  mb.command_length = send + 4;
-  mb.response_length = receive + 4;
-  mb.receive_cb = receive_cb;
-  mb.last = 0;
-  mb.retry = 0;
+static void _start_write() {
+  if (!state.write_ready) return;
 
+  // The minimum delay between modbus messages is 3.5 characters.  There are
+  // 11-bits per character in RTU mode.  Character time is calculated as
+  // follows:
+  //
+  //     char time = 11-bits / baud * 3.5
+  //
+  // At 9600 baud the minimum delay is 4.01ms.  At 19200 it's 2.005ms.  All
+  // supported higher baud rates require the 1.75ms minimum delay.  We round up
+  // and add 1ms to ensure the delay is never less than the required minimum
+  // using our 1ms RTC clock callback.
+  if (state.last_read &&
+      !rtc_expired(state.last_read + (cfg.baud == USART_BAUD_9600 ? 5 : 3)))
+    return;
+  state.last_read = 0;
+
+  state.write_ready = false;
   _set_dre_interrupt(true);
 }
 
 
-void modbus_read(uint16_t addr, modbus_read_cb_t cb) {
-  mb.read_cb = cb;
-  mb.addr = addr;
-  uint8_t cmd[4] = {(uint8_t)(addr >> 8), (uint8_t)addr, 0, 1};
+void modbus_func(uint8_t func, uint8_t send, const uint8_t *data,
+                 uint8_t receive, modbus_cb_t receive_cb) {
+  state.bytes = 0;
+  state.command_length = send + 4;
+  state.response_length = receive + 4;
+  state.receive_cb = receive_cb;
+  state.last_write = 0;
+  state.retry = 0;
+
+  ASSERT(state.command_length <= MODBUS_BUF_SIZE);
+  ASSERT(state.response_length <= MODBUS_BUF_SIZE);
+
+  state.command[0] = cfg.id;
+  state.command[1] = func;
+  memcpy(state.command + 2, data, send);
+  _write_word(state.command + send + 2, _crc16(state.command, send + 2), true);
+
+  state.busy = true;
+  state.write_ready = true;
+  _start_write();
+}
+
+
+void modbus_read(uint16_t addr, modbus_rw_cb_t cb) {
+  state.rw_cb = cb;
+  state.addr = addr;
+  uint8_t cmd[4] = {0, 0, 0, 1};
+  _write_word(cmd, addr, false);
   modbus_func(MODBUS_READ_OUTPUT_REG, 4, cmd, 3, _read_cb);
 }
 
 
-void modbus_write(uint16_t addr, uint16_t value, modbus_write_cb_t cb) {
-  mb.write_cb = cb;
-  mb.addr = addr;
-  uint8_t cmd[4] = {(uint8_t)(addr >> 8), (uint8_t)addr, (uint8_t)(value >> 8),
-                    (uint8_t)value};
+void modbus_write(uint16_t addr, uint16_t value, modbus_rw_cb_t cb) {
+  state.rw_cb = cb;
+  state.addr = addr;
+  uint8_t cmd[4];
+  _write_word(cmd, addr, false);
+  _write_word(cmd + 2, value, false);
   modbus_func(MODBUS_WRITE_OUTPUT_REG, 4, cmd, 4, _write_cb);
 }
 
 
 void modbus_rtc_callback() {
-  if (!mb.last || !rtc_expired(mb.last + MODBUS_TIMEOUT)) return;
+  _start_write();
+  if (!state.last_write || !rtc_expired(state.last_write + MODBUS_TIMEOUT))
+    return;
+  state.last_write = 0;
 
-  if (mb.debug && mb.bytes) {
+  if (cfg.debug && state.bytes) {
     const uint8_t buf_len = 8 * 2 + 1;
     char sent[buf_len];
     char received[buf_len];
 
-    format_hex_buf(sent, mb.command, mb.command_length);
-    format_hex_buf(received, mb.response, mb.bytes);
+    format_hex_buf(sent, state.command, state.command_length);
+    format_hex_buf(received, state.response, state.bytes);
 
     STATUS_DEBUG("modbus: sent 0x%s received 0x%s expected %u bytes",
-                 sent, received, mb.response_length);
+                 sent, received, state.response_length);
   }
 
-  if (mb.retry < 2 * MODBUS_RETRIES) _retry();
+  if (state.retry < 2 * MODBUS_RETRIES) _retry();
   else _timeout();
 }
 
 
 // Variable callbacks
-bool get_modbus_debug() {return mb.debug;}
-void set_modbus_debug(bool value) {mb.debug = value;}
-uint8_t get_modbus_id() {return mb.id;}
-void set_modbus_id(uint8_t id) {mb.id = id;}
-uint8_t get_modbus_baud() {return mb.baud;}
+bool get_modbus_debug() {return cfg.debug;}
+void set_modbus_debug(bool value) {cfg.debug = value;}
+uint8_t get_modbus_id() {return cfg.id;}
+void set_modbus_id(uint8_t id) {cfg.id = id;}
+uint8_t get_modbus_baud() {return cfg.baud;}
 
 
 void set_modbus_baud(uint8_t baud) {
-  mb.baud = (baud_t)baud;
-  usart_set_baud(&RS485_PORT, mb.baud);
+  cfg.baud = (baud_t)baud;
+  usart_set_baud(&RS485_PORT, cfg.baud);
 }
 
 
-uint8_t get_modbus_parity() {return mb.parity;}
+uint8_t get_modbus_parity() {return cfg.parity;}
 
 
 void set_modbus_parity(uint8_t parity) {
-  mb.parity = (parity_t)parity;
-  usart_set_parity(&RS485_PORT, mb.parity);
-}
-
-
-uint8_t get_modbus_stop() {return mb.stop;}
-
-
-void set_modbus_stop(uint8_t stop) {
-  mb.stop = (stop_t)stop;
-  usart_set_stop(&RS485_PORT, mb.stop);
+  cfg.parity = (parity_t)parity;
+  usart_set_parity(&RS485_PORT, cfg.parity);
+  usart_set_stop(&RS485_PORT, _get_stop());
 }
 
 
-bool get_modbus_connected() {return mb.connected;}
+uint8_t get_modbus_status() {return state.status;}
index 0a36d32dde344e71433200542fc98ead10a07ce7..42a7de2f48afb9d356cf7c7bdbfb5f4f517658c9 100644 (file)
@@ -99,14 +99,13 @@ typedef enum {
 
 
 typedef void (*modbus_cb_t)(uint8_t func, uint8_t bytes, const uint8_t *data);
-typedef void (*modbus_read_cb_t)(bool ok, uint16_t addr, uint16_t value);
-typedef void (*modbus_write_cb_t)(bool ok, uint16_t addr);
+typedef void (*modbus_rw_cb_t)(bool ok, uint16_t addr, uint16_t value);
 
 void modbus_init();
 void modbus_deinit();
 bool modbus_busy();
 void modbus_func(uint8_t func, uint8_t send, const uint8_t *data,
                  uint8_t receive, modbus_cb_t cb);
-void modbus_read(uint16_t addr, modbus_read_cb_t cb);
-void modbus_write(uint16_t addr, uint16_t value, modbus_write_cb_t cb);
+void modbus_read(uint16_t addr, modbus_rw_cb_t cb);
+void modbus_write(uint16_t addr, uint16_t value, modbus_rw_cb_t cb);
 void modbus_rtc_callback();
index 1023fb0ce43e069ff6ddfe79d943296bc0fc1280..a494ed92195751a4958fa0593af1c50c3b0d671c 100644 (file)
@@ -55,6 +55,7 @@ typedef struct {
   TC0_t *timer;
   DMA_CH_t *dma;
   uint8_t dma_trigger;
+
   bool slave;
   uint16_t microsteps;           // microsteps per full step
   bool reverse;
@@ -286,7 +287,7 @@ void motor_load_move(int motor) {
 }
 
 
-void motor_prep_move(int motor, float time, float target) {
+void motor_prep_move(int motor, float target) {
   // Validate input
   ASSERT(0 <= motor && motor < MOTORS);
   ASSERT(isfinite(target));
@@ -314,7 +315,7 @@ void motor_prep_move(int motor, float time, float target) {
   if (m->negative) steps = -steps;
 
   // We use clock / 2
-  float seg_clocks = time * (F_CPU * 60 / 2);
+  float seg_clocks = SEGMENT_TIME * (F_CPU * 60 / 2);
   float ticks_per_step = round(seg_clocks / steps);
 
   // Limit clock if step rate is too fast, disable if too slow
@@ -336,7 +337,11 @@ void motor_prep_move(int motor, float time, float target) {
     m->power_timeout = rtc_get_time() + MOTOR_IDLE_TIMEOUT * 1000;
     break;
 
-  default: break;
+  default: // Disabled
+    m->timer_period = 0;
+    m->encoder = m->commanded = m->position;
+    m->error = 0;
+    break;
   }
   _update_power(motor);
 
index bcfffd8e0219aed9ac4bb3b699b8317c5d935b81..0940cd2db106a09ec1b08e5e86a83f23c7937d88 100644 (file)
@@ -54,4 +54,4 @@ stat_t motor_rtc_callback();
 
 void motor_end_move(int motor);
 void motor_load_move(int motor);
-void motor_prep_move(int motor, float time, float target);
+void motor_prep_move(int motor, float target);
index 80d2d8a62e67ffee6ee8520b5498d93d6d5166b6..a510eba69930c0440cf583e3089e3f537fb12551 100644 (file)
@@ -120,7 +120,7 @@ void pwm_spindle_init() {
 }
 
 
-void pwm_spindle_deinit() {
+void pwm_spindle_deinit(deinit_cb_t cb) {
   _set_enable(false);
 
   // Float PWM output pin
@@ -128,6 +128,8 @@ void pwm_spindle_deinit() {
 
   // Disable clock
   TIMER_PWM.CTRLA = 0;
+
+  cb();
 }
 
 
index 996020db1429e4aa837ee978728845b66d1507d4..132e94b486a426b1acc22b3b2445b3cf79059e3c 100644 (file)
 
 #pragma once
 
+#include "spindle.h"
+
 
 void pwm_spindle_init();
-void pwm_spindle_deinit();
+void pwm_spindle_deinit(deinit_cb_t cb);
 void pwm_spindle_set(float speed);
 float pwm_spindle_get();
 void pwm_spindle_stop();
index 11701c42263d80f5786d9e2756f15737d057e860..5e9d032afd9c97dbf825c0cc2bd449a163f9a24e 100644 (file)
 #include "usart.h"
 #include "rtc.h"
 #include "vars.h"
-#include "pgmspace.h"
 
-#include <stdio.h>
-#include <stdbool.h>
 
-
-static bool _requested = false;
 static bool _full = false;
 static uint32_t _last = 0;
 
 
-void report_request() {_requested = true;}
-void report_request_full() {_requested = _full = true;}
+void report_request_full() {_full = true;}
 
 
 void report_callback() {
-  if (_requested && usart_tx_empty()) {
-    uint32_t now = rtc_get_time();
-    if (now - _last < 250) return;
-    _last = now;
-
-    vars_report(_full);
-    _requested = _full = false;
-  }
+  // Wait until output buffer is empty
+  if (!usart_tx_empty()) return;
+
+  // Limit frequency
+  uint32_t now = rtc_get_time();
+  if (now - _last < REPORT_RATE) return;
+  _last = now;
+
+  // Report vars
+  vars_report(_full);
+  _full = false;
 }
index 2833637c7f91fb16c1d433f9da73d8ad8abf7dfa..4a7dcfffe6c8da6d6c01e7df9c50e34ceaaf8f16 100644 (file)
@@ -30,6 +30,5 @@
 
 #include "status.h"
 
-void report_request();
 void report_request_full();
 void report_callback();
index 1c7a779fc93261e4fef652c51c360081e50db3ab..a3779598704110533f42c111141c4ca5e886c897 100644 (file)
@@ -33,6 +33,7 @@
 #include "modbus.h"
 #include "motor.h"
 #include "lcd.h"
+#include "vfd_spindle.h"
 
 #include <avr/io.h>
 #include <avr/interrupt.h>
@@ -52,6 +53,7 @@ ISR(RTC_OVF_vect) {
   analog_rtc_callback();
   io_rtc_callback();
   modbus_rtc_callback();
+  vfd_spindle_rtc_callback();
   if (!(ticks & 255)) motor_rtc_callback();
   wdt_reset();
 }
index 0af9ccb01074fbba3b19ea55736ea58d49215e8d..2c96215447795d97d4aac723ba90acf90fb05e87 100644 (file)
 \******************************************************************************/
 
 #include "spindle.h"
-
+#include "pwm_spindle.h"
+#include "huanyang.h"
+#include "vfd_spindle.h"
+#include "vfd_test.h"
 #include "config.h"
 #include "pgmspace.h"
 
 #include <math.h>
 
 
-typedef enum {
-  SPINDLE_TYPE_DISABLED,
-#define SPINDLE(NAME) SPINDLE_TYPE_##NAME,
-#include "spindle.def"
-#undef SPINDLE
-} spindle_type_t;
-
-
-// Function decls
-#define SPINDLE(NAME)                         \
-  void NAME##_init();                         \
-  void NAME##_deinit();                       \
-  void NAME##_set(float speed);               \
-  float NAME##_get();                         \
-  void NAME##_stop();
-#include "spindle.def"
-#undef SPINDLE
-
-
-typedef struct {
+static struct {
   spindle_type_t type;
+  float override;
   float speed;
   bool reversed;
   float min_rpm;
   float max_rpm;
-} spindle_t;
+
+  spindle_type_t next_type;
+} spindle = {SPINDLE_TYPE_DISABLED, 1};
 
 
-static spindle_t spindle = {SPINDLE_TYPE_DISABLED,};
+spindle_type_t spindle_get_type() {return spindle.type;}
 
 
 void spindle_set_speed(float speed) {
   spindle.speed = speed;
 
+  speed *= spindle.override;
+
   bool negative = speed < 0;
   if (spindle.max_rpm <= fabs(speed)) speed = negative ? -1 : 1;
   else if (fabs(speed) < spindle.min_rpm) speed = 0;
@@ -76,9 +65,10 @@ void spindle_set_speed(float speed) {
 
   switch (spindle.type) {
   case SPINDLE_TYPE_DISABLED: break;
-#define SPINDLE(NAME) case SPINDLE_TYPE_##NAME: NAME##_set(speed); break;
-#include "spindle.def"
-#undef SPINDLE
+  case SPINDLE_TYPE_PWM: pwm_spindle_set(speed); break;
+  case SPINDLE_TYPE_HUANYANG: huanyang_set(speed); break;
+  case SPINDLE_TYPE_TEST: vfd_test_set(speed); break;
+  default: vfd_spindle_set(speed); break;
   }
 }
 
@@ -88,9 +78,10 @@ float spindle_get_speed() {
 
   switch (spindle.type) {
   case SPINDLE_TYPE_DISABLED: break;
-#define SPINDLE(NAME) case SPINDLE_TYPE_##NAME: speed = NAME##_get(); break;
-#include "spindle.def"
-#undef SPINDLE
+  case SPINDLE_TYPE_PWM: speed = pwm_spindle_get(); break;
+  case SPINDLE_TYPE_HUANYANG: speed = huanyang_get(); break;
+  case SPINDLE_TYPE_TEST: speed = vfd_test_get(); break;
+  default: speed = vfd_spindle_get(); break;
   }
 
   return speed * spindle.max_rpm;
@@ -100,9 +91,10 @@ float spindle_get_speed() {
 void spindle_stop() {
   switch (spindle.type) {
   case SPINDLE_TYPE_DISABLED: break;
-#define SPINDLE(NAME) case SPINDLE_TYPE_##NAME: NAME##_stop(); break;
-#include "spindle.def"
-#undef SPINDLE
+  case SPINDLE_TYPE_PWM: pwm_spindle_stop(); break;
+  case SPINDLE_TYPE_HUANYANG: huanyang_stop(); break;
+  case SPINDLE_TYPE_TEST: vfd_test_stop(); break;
+  default: vfd_spindle_stop(); break;
   }
 }
 
@@ -112,43 +104,51 @@ static void _update_speed() {spindle_set_speed(spindle.speed);}
 
 
 // Var callbacks
-uint8_t get_spindle_type() {return spindle.type;}
+uint8_t get_tool_type() {return spindle.type;}
+
 
+static void _deinit_cb() {
+  spindle.type = spindle.next_type;
+  spindle.next_type = SPINDLE_TYPE_DISABLED;
 
-void set_spindle_type(uint8_t value) {
-  if (value != spindle.type) {
-    float speed = spindle.speed;
+  switch (spindle.type) {
+  case SPINDLE_TYPE_DISABLED: break;
+  case SPINDLE_TYPE_PWM: pwm_spindle_init(); break;
+  case SPINDLE_TYPE_HUANYANG: huanyang_init(); break;
+  case SPINDLE_TYPE_TEST: vfd_test_init(); break;
+  default: vfd_spindle_init(); break;
+  }
+
+  spindle_set_speed(spindle.speed);
+}
 
-    switch (spindle.type) {
-    case SPINDLE_TYPE_DISABLED: break;
-#define SPINDLE(NAME) case SPINDLE_TYPE_##NAME: NAME##_deinit(); break;
-#include "spindle.def"
-#undef SPINDLE
-    }
 
-    spindle.type = (spindle_type_t)value;
+void set_tool_type(uint8_t value) {
+  if (value == spindle.type) return;
 
-    switch (spindle.type) {
-    case SPINDLE_TYPE_DISABLED: break;
-#define SPINDLE(NAME) case SPINDLE_TYPE_##NAME: NAME##_init(); break;
-#include "spindle.def"
-#undef SPINDLE
-    }
+  spindle_type_t old_type = spindle.type;
+  spindle.next_type = (spindle_type_t)value;
+  spindle.type = SPINDLE_TYPE_DISABLED;
 
-    spindle_set_speed(speed);
+  switch (old_type) {
+  case SPINDLE_TYPE_DISABLED: _deinit_cb(); break;
+  case SPINDLE_TYPE_PWM: pwm_spindle_deinit(_deinit_cb); break;
+  case SPINDLE_TYPE_HUANYANG: huanyang_deinit(_deinit_cb); break;
+  case SPINDLE_TYPE_TEST: vfd_test_deinit(_deinit_cb); break;
+  default: vfd_spindle_deinit(_deinit_cb); break;
   }
 }
 
 
 void set_speed(float speed) {spindle_set_speed(speed);}
 float get_speed() {return spindle_get_speed();}
-bool get_spin_reversed() {return spindle.reversed;}
+bool get_tool_reversed() {return spindle.reversed;}
 
 
-void set_spin_reversed(bool reversed) {
+void set_tool_reversed(bool reversed) {
   if (spindle.reversed != reversed) {
     spindle.reversed = reversed;
-    spindle_set_speed(spindle.speed);
+    _update_speed();
   }
 }
 
@@ -157,3 +157,10 @@ float get_max_spin() {return spindle.max_rpm;}
 void set_max_spin(float value) {spindle.max_rpm = value; _update_speed();}
 float get_min_spin() {return spindle.min_rpm;}
 void set_min_spin(float value) {spindle.min_rpm = value; _update_speed();}
+uint16_t get_speed_override() {return spindle.override * 1000;}
+
+
+void set_speed_override(uint16_t value) {
+  spindle.override = value / 1000.0;
+  _update_speed();
+}
diff --git a/src/avr/src/spindle.def b/src/avr/src/spindle.def
deleted file mode 100644 (file)
index 1022568..0000000
+++ /dev/null
@@ -1,30 +0,0 @@
-/******************************************************************************\
-
-                 This file is part of the Buildbotics firmware.
-
-                   Copyright (c) 2015 - 2018, Buildbotics LLC
-                              All rights reserved.
-
-      This file ("the software") is free software: you can redistribute it
-      and/or modify it under the terms of the GNU General Public License,
-       version 2 as published by the Free Software Foundation. You should
-       have received a copy of the GNU General Public License, version 2
-      along with the software. If not, see <http://www.gnu.org/licenses/>.
-
-      The software is distributed in the hope that it will be useful, but
-           WITHOUT ANY WARRANTY; without even the implied warranty of
-       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
-                Lesser General Public License for more details.
-
-        You should have received a copy of the GNU Lesser General Public
-                 License along with the software.  If not, see
-                        <http://www.gnu.org/licenses/>.
-
-                 For information regarding this software email:
-                   "Joseph Coffland" <joseph@buildbotics.com>
-
-\******************************************************************************/
-
-SPINDLE(pwm_spindle)
-SPINDLE(huanyang)
-SPINDLE(yl600)
index b15eb00ab3b00c16b571ce364abe15a56cdc976a..b1dd5ce70135fd445ad975a346fa71b24bad3b84 100644 (file)
 #include <stdbool.h>
 
 
+typedef enum {
+  SPINDLE_TYPE_DISABLED,
+  SPINDLE_TYPE_PWM,
+  SPINDLE_TYPE_HUANYANG,
+  SPINDLE_TYPE_TEST,
+  SPINDLE_TYPE_CUSTOM,
+  SPINDLE_TYPE_YL600,
+  SPINDLE_TYPE_AC_TECH,
+} spindle_type_t;
+
+
+typedef void (*deinit_cb_t)();
+
+
+spindle_type_t spindle_get_type();
 void spindle_set_speed(float speed);
 float spindle_get_speed();
 void spindle_stop();
index d39c010c16732d5d971a475901e876f58afd3dd2..4afbeaa4ad1680ec1043e206f7d2253f0228e25f 100644 (file)
@@ -35,7 +35,6 @@
 #include "jog.h"
 #include "estop.h"
 #include "seek.h"
-#include "report.h"
 
 #include <stdio.h>
 
@@ -88,14 +87,12 @@ static void _set_state(state_t state) {
   if (s.state == state) return; // No change
   if (s.state == STATE_ESTOPPED) return; // Can't leave EStop state
   s.state = state;
-  report_request();
 }
 
 
 static void _set_hold_reason(hold_reason_t reason) {
   if (s.hold_reason == reason) return; // No change
   s.hold_reason = reason;
-  report_request();
 }
 
 
index 451267dd382ff75316292efb9a1a883f67b73767..9c67adec99b8a0bf2a7433660c769d9987131b73 100644 (file)
@@ -73,6 +73,7 @@ stat_t status_message_P(const char *location, status_level_t level,
 
   // Message
   if (msg && pgm_read_byte(msg)) {
+    // TODO escape invalid chars
     va_start(args, msg);
     vfprintf_P(stdout, msg, args);
     va_end(args);
index 793bd1bc03ae9cd65dccf9164f4d093696da2a11..019e95c07696b1000266b1da9b9fd72eea5f3804 100644 (file)
@@ -33,7 +33,6 @@
 #include "estop.h"
 #include "util.h"
 #include "cpp_magic.h"
-#include "report.h"
 #include "exec.h"
 #include "drv8711.h"
 
@@ -100,7 +99,6 @@ void st_shutdown() {
 
 void st_enable() {
   if (!estop_triggered()) OUTSET_PIN(MOTOR_ENABLE_PIN); // Active high
-  report_request();
 }
 
 
@@ -194,19 +192,17 @@ static void _load_move() {
 ISR(STEP_TIMER_ISR) {_load_move();}
 
 
-void st_prep_line(float time, const float target[]) {
+void st_prep_line(const float target[]) {
   // Trap conditions that would prevent queuing the line
   ASSERT(!st.move_ready);
-  ASSERT(isfinite(time));
-  ASSERT(time * STEP_TIMER_FREQ * 60 <= 0xffff);
 
   // Setup segment parameters
   st.move_type = MOVE_TYPE_LINE;
-  st.clock_period = round(time * STEP_TIMER_FREQ * 60);
+  st.clock_period = SEGMENT_TIME * 60 * STEP_TIMER_FREQ;
 
   // Prepare motor moves
   for (int motor = 0; motor < MOTORS; motor++)
-    motor_prep_move(motor, time, target[motor_get_axis(motor)]);
+    motor_prep_move(motor, target[motor_get_axis(motor)]);
 
   st.move_queued = true; // signal prep buffer ready (do this last)
 }
index 4ede34b67e57123def0beec0ea35a67dda882199..f3ec2773ae3f5330b4c97be831210672e260a16f 100644 (file)
@@ -35,5 +35,5 @@ void stepper_init();
 void st_shutdown();
 void st_enable();
 bool st_is_busy();
-void st_prep_line(float time, const float target[]);
+void st_prep_line(const float target[]);
 void st_prep_dwell(float seconds);
index aa92dd4b5e39518f7a0841a1d4ea2095322772bb..227afadf178491cb7682bebb04cc54ed3e64daf4 100644 (file)
 // String
 bool type_eq_str(str a, str b) {return a == b;}
 void type_print_str(str s) {printf_P(PSTR("\"%s\""), s);}
-float type_str_to_float(str s) {return 0;}
-str type_parse_str(const char *s) {return s;}
+str type_parse_str(const char *s, stat_t *) {return s;}
 
 // Program string
 bool type_eq_pstr(pstr a, pstr b) {return a == b;}
 void type_print_pstr(pstr s) {printf_P(PSTR("\"%" PRPSTR "\""), s);}
-const char *type_parse_pstr(const char *value) {return value;}
-float type_pstr_to_float(pstr s) {return 0;}
+const char *type_parse_pstr(const char *value, stat_t *) {return value;}
 
 
 // Flags
 bool type_eq_flags(flags a, flags b) {return a == b;}
-float type_flags_to_float(flags x) {return x;}
 
 
 void type_print_flags(flags x) {
@@ -67,12 +64,11 @@ void type_print_flags(flags x) {
   print_status_flags(x);
 }
 
-flags type_parse_flags(const char *s) {return 0;} // Not used
+flags type_parse_flags(const char *s, stat_t *) {return 0;} // Not used
 
 
 // Float
 bool type_eq_f32(float a, float b) {return a == b || (isnan(a) && isnan(b));}
-float type_f32_to_float(float x) {return x;}
 
 
 void type_print_f32(float x) {
@@ -100,75 +96,122 @@ void type_print_f32(float x) {
 }
 
 
-float type_parse_f32(const char *value) {
+float type_parse_f32(const char *value, stat_t *status) {
   while (*value && isspace(*value)) value++;
 
   if (*value == ':') {
     value++;
-    if (strnlen(value, 6) != 6) return NAN;
+    if (strnlen(value, 6) != 6) {
+      if (status) *status = STAT_INVALID_VALUE;
+      return NAN;
+    }
 
     float f;
-    return b64_decode_float(value, &f) ? f : NAN;
+    if (b64_decode_float(value, &f)) return f;
+    else {
+      if (status) *status = STAT_BAD_FLOAT;
+      return NAN;
+    }
   }
 
-  return strtod(value, 0);
+  char *endptr = 0;
+  float x = strtod(value, &endptr);
+
+  if (endptr == value) {
+    if (status) *status = STAT_BAD_FLOAT;
+    return NAN;
+  }
+
+  return x;
 }
 
 
 // bool
 bool type_eq_b8(bool a, bool b) {return a == b;}
-float type_b8_to_float(bool x) {return x;}
 void type_print_b8(bool x) {printf_P(x ? PSTR("true") : PSTR("false"));}
 
 
-bool type_parse_b8(const char *value) {
-  return !strcasecmp(value, "true") || type_parse_f32(value);
+bool type_parse_b8(const char *value, stat_t *status) {
+  return !strcasecmp(value, "true") || type_parse_f32(value, status);
 }
 
 
 // s8
 bool type_eq_s8(s8 a, s8 b) {return a == b;}
-float type_s8_to_float(s8 x) {return x;}
 void type_print_s8(s8 x) {printf_P(PSTR("%" PRIi8), x);}
-s8 type_parse_s8(const char *value) {return strtol(value, 0, 0);}
+
+
+s8 type_parse_s8(const char *value, stat_t *status) {
+  char *endptr = 0;
+  s8 x = strtol(value, &endptr, 0);
+  if (endptr == value && status) *status = STAT_BAD_INT;
+  return x;
+}
 
 
 // u8
 bool type_eq_u8(u8 a, u8 b) {return a == b;}
-float type_u8_to_float(u8 x) {return x;}
 void type_print_u8(u8 x) {printf_P(PSTR("%" PRIu8), x);}
-u8 type_parse_u8(const char *value) {return strtol(value, 0, 0);}
+
+
+u8 type_parse_u8(const char *value, stat_t *status) {
+  char *endptr = 0;
+  u8 x = strtoul(value, &endptr, 0);
+  if (endptr == value && status) *status = STAT_BAD_INT;
+  return x;
+}
 
 
 // u16
 bool type_eq_u16(u16 a, u16 b) {return a == b;}
-float type_u16_to_float(u16 x) {return x;}
 void type_print_u16(u16 x) {printf_P(PSTR("%" PRIu16), x);}
-u16 type_parse_u16(const char *value) {return strtoul(value, 0, 0);}
+
+
+u16 type_parse_u16(const char *value, stat_t *status) {
+  char *endptr = 0;
+  u16 x = strtoul(value, &endptr, 0);
+  if (endptr == value && status) *status = STAT_BAD_INT;
+  return x;
+}
 
 
 // s32
 bool type_eq_s32(s32 a, s32 b) {return a == b;}
-float type_s32_to_float(s32 x) {return x;}
 void type_print_s32(s32 x) {printf_P(PSTR("%" PRIi32), x);}
-s32 type_parse_s32(const char *value) {return strtol(value, 0, 0);}
+
+
+s32 type_parse_s32(const char *value, stat_t *status) {
+  char *endptr = 0;
+  s32 x = strtol(value, &endptr, 0);
+  if (endptr == value && status) *status = STAT_BAD_INT;
+  return x;
+}
 
 
 // u32
 bool type_eq_u32(u32 a, u32 b) {return a == b;}
-float type_u32_to_float(u32 x) {return x;}
 void type_print_u32(u32 x) {printf_P(PSTR("%" PRIu32), x);}
-u32 type_parse_u32(const char *value) {return strtol(value, 0, 0);}
 
 
-type_u type_parse(type_t type, const char *s) {
+u32 type_parse_u32(const char *value, stat_t *status) {
+  char *endptr = 0;
+  u32 x = strtoul(value, &endptr, 0);
+  if (endptr == value && status) *status = STAT_BAD_INT;
+  return x;
+}
+
+
+type_u type_parse(type_t type, const char *s, stat_t *status) {
   type_u value;
 
+  if (status) *status = STAT_OK;
+
   switch (type) {
 #define TYPEDEF(TYPE, ...)                                              \
-    case TYPE_##TYPE: value._##TYPE = type_parse_##TYPE(s); break;
+    case TYPE_##TYPE: value._##TYPE = type_parse_##TYPE(s, status); break;
 #include "type.def"
 #undef TYPEDEF
+    default: if (status) *status = STAT_INVALID_TYPE;
   }
 
   return value;
@@ -183,14 +226,3 @@ void type_print(type_t type, type_u value) {
 #undef TYPEDEF
   }
 }
-
-
-float type_to_float(type_t type, type_u value) {
-  switch (type) {
-#define TYPEDEF(TYPE, ...)                                          \
-    case TYPE_##TYPE: return type_##TYPE##_to_float(value._##TYPE);
-#include "type.def"
-#undef TYPEDEF
-  }
-  return 0;
-}
index 1ec18d8480fa268e037bb5084d8a25b4c8413bb2..322ebd66b823dad534ea8e2d64ae76e9925402a9 100644 (file)
@@ -28,6 +28,7 @@
 #pragma once
 
 #include "pgmspace.h"
+#include "status.h"
 
 #include <stdint.h>
 #include <stdbool.h>
@@ -53,16 +54,14 @@ typedef union {
 
 
 // Define functions
-#define TYPEDEF(TYPE, DEF)                           \
-  pstr type_get_##TYPE##_name_pgm();                 \
-  bool type_eq_##TYPE(TYPE a, TYPE b);               \
-  TYPE type_parse_##TYPE(const char *s);             \
-  void type_print_##TYPE(TYPE x);                    \
-  float type_##TYPE##_to_float(TYPE x);
+#define TYPEDEF(TYPE, DEF)                                  \
+  pstr type_get_##TYPE##_name_pgm();                        \
+  bool type_eq_##TYPE(TYPE a, TYPE b);                      \
+  TYPE type_parse_##TYPE(const char *s, stat_t *status);    \
+  void type_print_##TYPE(TYPE x);
 #include "type.def"
 #undef TYPEDEF
 
 
-type_u type_parse(type_t type, const char *s);
+type_u type_parse(type_t type, const char *s, stat_t *status);
 void type_print(type_t type, type_u value);
-float type_to_float(type_t type, type_u value);
index 61137fe04d2ebfe3dedde1214144558090205dd1..f39be9345d0c5263b4ea0b072b0d5bdcc1c61651 100644 (file)
@@ -93,3 +93,9 @@ void format_hex_buf(char *buf, const uint8_t *data, unsigned len) {
 
   buf[i * 2] = 0;
 }
+
+
+void print_vector(float v[4]) {
+  printf_P(PSTR("%f %f %f %f\n"),
+           (double)v[0], (double)v[1], (double)v[2], (double)v[3]);
+}
index 300fb1a9c9f692d71ea04ce91558fbd1472ecbf8..dd1b754e40d3a3f0b434ae06d0b1db6cb85672f5 100644 (file)
@@ -69,6 +69,7 @@ int8_t decode_hex_nibble(char c);
 bool decode_float(char **s, float *f);
 stat_t decode_axes(char **cmd, float axes[AXES]);
 void format_hex_buf(char *buf, const uint8_t *data, unsigned len);
+void print_vector(float v[4]);
 
 // Constants
 #define MM_PER_INCH 25.4
index 3e9bda6806f12facc279c5cd020b0ecc8df5b8f4..5a4b0cdbd228d5fae88c7a8888a6f1fe860f46fe 100644 (file)
@@ -98,10 +98,9 @@ typedef struct {
 } var_info_t;
 
 
-// Var names & help
-#define VAR(NAME, CODE, TYPE, INDEX, SET, REPORT, HELP)      \
-  static const char NAME##_name[] PROGMEM = #NAME;          \
-  static const char NAME##_help[] PROGMEM = HELP;
+// Var names
+#define VAR(NAME, CODE, TYPE, INDEX, SET, REPORT)           \
+  static const char NAME##_name[] PROGMEM = #NAME;
 
 #include "vars.def"
 #undef VAR
@@ -308,30 +307,23 @@ stat_t vars_set(const char *name, const char *value) {
   if (!_find_var(name, &info)) return STAT_UNRECOGNIZED_NAME;
   if (!info.set.ptr) return STAT_READ_ONLY;
 
-  _set(info.type, info.index, info.set, type_parse(info.type, value));
+  stat_t status;
+  type_u x = type_parse(info.type, value, &status);
+  if (status == STAT_OK) _set(info.type, info.index, info.set, x);
 
-  return STAT_OK;
-}
-
-
-float vars_get_number(const char *name) {
-  var_info_t info;
-  if (!_find_var(name, &info)) return 0;
-  return type_to_float(info.type, _get(info.type, info.index, info.get));
+  return status;
 }
 
 
 void vars_print_json() {
   bool first = true;
   static const char fmt[] PROGMEM =
-    "\"%s\":{\"name\":\"%" PRPSTR "\",\"type\":\"%" PRPSTR "\","
-    "\"help\":\"%" PRPSTR "\"";
+    "\"%s\":{\"name\":\"%" PRPSTR "\",\"type\":\"%" PRPSTR "\"";
   static const char index_fmt[] PROGMEM = ",\"index\":\"%s\"";
 
 #define VAR(NAME, CODE, TYPE, INDEX, ...)                               \
   if (first) first = false; else putchar(',');                          \
-  printf_P(fmt, #CODE, NAME##_name, type_get_##TYPE##_name_pgm(),       \
-           NAME##_help);                                                \
+  printf_P(fmt, #CODE, NAME##_name, type_get_##TYPE##_name_pgm());      \
   IF(INDEX)(printf_P(index_fmt, INDEX##_LABEL));                        \
   putchar('}');
 #include "vars.def"
@@ -352,7 +344,9 @@ stat_t command_var(char *cmd) {
   char *value = strchr(cmd, '=');
   if (value) {
     *value++ = 0;
-    return vars_set(cmd, value);
+    stat_t status = vars_set(cmd, value);
+    value[-1] = '='; // For error reporting
+    return status;
   }
 
   return vars_print(cmd);
@@ -377,16 +371,17 @@ stat_t command_sync_var(char *cmd) {
   if (!_find_var(cmd + 1, &info)) return STAT_UNRECOGNIZED_NAME;
   if (!info.set.ptr) return STAT_READ_ONLY;
 
+  stat_t status;
   var_cmd_t buffer;
 
   buffer.type = info.type;
   buffer.index = info.index;
   buffer.set = info.set;
-  buffer.value = type_parse(info.type, value);
+  buffer.value = type_parse(info.type, value, &status);
 
-  command_push(*cmd, &buffer);
+  if (status == STAT_OK) command_push(*cmd, &buffer);
 
-  return STAT_OK;
+  return status;
 }
 
 
index 91a8b95705e935b58a2d6ddf79fa509c19f086b6..944ef4d3de555ee5750d2eb46610d11520310084 100644 (file)
 #define MOTORS_LABEL "0123"
 #define OUTS_LABEL   "ed12f"
 #define ANALOG_LABEL "12"
+#define VFDREG_LABEL "0123456789abcdefghijklmnopqrstuv"
 
-// VAR(name, code, type, index, settable, report, help)
+// VAR(name, code, type, index, settable, report)
 
 // Motor
-VAR(motor_axis,      an, u8,    MOTORS, 1, 1, "Maps motor to axis")
+VAR(motor_axis,      an, u8,    MOTORS, 1, 1) // Maps motor to axis
 
-VAR(power_mode,      pm, u8,    MOTORS, 1, 1, "Motor power mode")
-VAR(drive_current,   dc, f32,   MOTORS, 1, 1, "Max motor drive current")
-VAR(idle_current,    ic, f32,   MOTORS, 1, 1, "Motor idle current")
+VAR(power_mode,      pm, u8,    MOTORS, 1, 1) // Motor power mode
+VAR(drive_current,   dc, f32,   MOTORS, 1, 1) // Max motor drive current
+VAR(idle_current,    ic, f32,   MOTORS, 1, 1) // Motor idle current
 
-VAR(reverse,         rv, b8,    MOTORS, 1, 1, "Reverse motor polarity")
-VAR(microstep,       mi, u16,   MOTORS, 1, 1, "Microsteps per full step")
-VAR(velocity_max,    vm, f32,   MOTORS, 1, 1, "Maxium vel in mm/min")
-VAR(accel_max,       am, f32,   MOTORS, 1, 1, "Maxium accel in mm/min^2")
-VAR(jerk_max,        jm, f32,   MOTORS, 1, 1, "Maxium jerk in mm/min^3")
-VAR(step_angle,      sa, f32,   MOTORS, 1, 1, "In degrees per full step")
-VAR(travel,          tr, f32,   MOTORS, 1, 1, "Travel in mm/rev")
+VAR(reverse,         rv, b8,    MOTORS, 1, 1) // Reverse motor polarity
+VAR(microstep,       mi, u16,   MOTORS, 1, 1) // Microsteps per full step
+VAR(velocity_max,    vm, f32,   MOTORS, 1, 1) // Maxium vel in mm/min
+VAR(accel_max,       am, f32,   MOTORS, 1, 1) // Maxium accel in mm/min^2
+VAR(jerk_max,        jm, f32,   MOTORS, 1, 1) // Maxium jerk in mm/min^3
+VAR(step_angle,      sa, f32,   MOTORS, 1, 1) // In degrees per full step
+VAR(travel,          tr, f32,   MOTORS, 1, 1) // Travel in mm/rev
 
-VAR(min_soft_limit,  tn, f32,   MOTORS, 1, 1, "Min soft limit")
-VAR(max_soft_limit,  tm, f32,   MOTORS, 1, 1, "Max soft limit")
-VAR(homed,            h, b8,    MOTORS, 1, 1, "Motor homed status")
+VAR(min_soft_limit,  tn, f32,   MOTORS, 1, 1) // Min soft limit
+VAR(max_soft_limit,  tm, f32,   MOTORS, 1, 1) // Max soft limit
+VAR(homed,            h, b8,    MOTORS, 1, 1) // Motor homed status
 
-VAR(active_current,  ac, f32,   MOTORS, 0, 1, "Motor current now")
-VAR(driver_flags,    df, u16,   MOTORS, 0, 1, "Motor driver flags")
-VAR(status_strings,  ds, flags, MOTORS, 0, 1, "Motor driver status")
-VAR(driver_stalled,  sl, b8,    MOTORS, 0, 1, "Motor driver status")
-VAR(encoder,         en, s32,   MOTORS, 0, 0, "Motor encoder")
-VAR(error,           ee, s32,   MOTORS, 0, 0, "Motor position error")
+VAR(active_current,  ac, f32,   MOTORS, 0, 1) // Motor current now
+VAR(driver_flags,    df, u16,   MOTORS, 0, 1) // Motor driver flags
+VAR(status_strings,  ds, flags, MOTORS, 0, 1) // Motor driver status
+VAR(driver_stalled,  sl, b8,    MOTORS, 0, 1) // Motor driver status
+VAR(encoder,         en, s32,   MOTORS, 0, 0) // Motor encoder
+VAR(error,           ee, s32,   MOTORS, 0, 0) // Motor position error
 
-VAR(motor_fault,     fa, b8,    0,      0, 1, "Motor fault status")
+VAR(motor_fault,     fa, b8,    0,      0, 1) // Motor fault status
 
 // Switches
-VAR(min_sw_mode,     ls, u8,    MOTORS, 1, 1, "Minimum switch mode")
-VAR(max_sw_mode,     xs, u8,    MOTORS, 1, 1, "Maximum switch mode")
-VAR(estop_mode,      et, u8,    0,      1, 1, "Estop switch mode")
-VAR(probe_mode,      pt, u8,    0,      1, 1, "Probe switch mode")
-VAR(min_switch,      lw, u8,    MOTORS, 0, 1, "Minimum switch state")
-VAR(max_switch,      xw, u8,    MOTORS, 0, 1, "Maximum switch state")
-VAR(estop_switch,    ew, u8,    0,      0, 1, "Estop switch state")
-VAR(probe_switch,    pw, u8,    0,      0, 1, "Probe switch state")
+VAR(min_sw_mode,     ls, u8,    MOTORS, 1, 1) // Minimum switch mode
+VAR(max_sw_mode,     xs, u8,    MOTORS, 1, 1) // Maximum switch mode
+VAR(estop_mode,      et, u8,    0,      1, 1) // Estop switch mode
+VAR(probe_mode,      pt, u8,    0,      1, 1) // Probe switch mode
+VAR(min_switch,      lw, u8,    MOTORS, 0, 1) // Minimum switch state
+VAR(max_switch,      xw, u8,    MOTORS, 0, 1) // Maximum switch state
+VAR(estop_switch,    ew, u8,    0,      0, 1) // Estop switch state
+VAR(probe_switch,    pw, u8,    0,      0, 1) // Probe switch state
 
 // Axis
-VAR(axis_position,    p, f32,   AXES,   0, 1, "Axis position")
+VAR(axis_position,    p, f32,   AXES,   0, 1) // Axis position
 
 // Outputs
-VAR(output_active,   oa, b8,    OUTS,   1, 1, "Output pin active")
-VAR(output_state,    os, u8,    OUTS,   0, 1, "Output pin state")
-VAR(output_mode,     om, u8,    OUTS,   1, 1, "Output pin mode")
+VAR(output_active,   oa, b8,    OUTS,   1, 1) // Output pin active
+VAR(output_state,    os, u8,    OUTS,   0, 1) // Output pin state
+VAR(output_mode,     om, u8,    OUTS,   1, 1) // Output pin mode
 
 // Analog
-VAR(analog_input,    ai, f32,   ANALOG, 0, 0, "Analog input pins")
+VAR(analog_input,    ai, f32,   ANALOG, 0, 0) // Analog input pins
 
 // Spindle
-VAR(spindle_type,    st, u8,    0,      1, 1, "DISABLED=0, PWM=1 or HUANYANG=2")
-VAR(speed,            s, f32,   0,      1, 1, "Current spindle speed")
-VAR(spin_reversed,   sr, b8,    0,      1, 1, "Reverse spin")
-VAR(max_spin,        sx, f32,   0,      1, 1, "Maximum spindle speed")
-VAR(min_spin,        sm, f32,   0,      1, 1, "Minimum spindle speed")
+VAR(tool_type,       st, u8,    0,      1, 1) // See spindle.c
+VAR(speed,            s, f32,   0,      1, 1) // Current spindle speed
+VAR(tool_reversed,   sr, b8,    0,      1, 1) // Reverse tool
+VAR(max_spin,        sx, f32,   0,      1, 1) // Maximum spindle speed
+VAR(min_spin,        sm, f32,   0,      1, 1) // Minimum spindle speed
 
 // PWM spindle
-VAR(pwm_invert,      pi, b8,    0,      1, 1, "Inverted spindle PWM")
-VAR(pwm_min_duty,    nd, f32,   0,      1, 1, "Minimum PWM duty cycle")
-VAR(pwm_max_duty,    md, f32,   0,      1, 1, "Maximum PWM duty cycle")
-VAR(pwm_duty,        pd, f32,   0,      0, 1, "Current PWM duty cycle")
-VAR(pwm_freq,        sf, u16,   0,      1, 1, "Spindle PWM frequency in Hz")
+VAR(pwm_invert,      pi, b8,    0,      1, 1) // Inverted spindle PWM
+VAR(pwm_min_duty,    nd, f32,   0,      1, 1) // Minimum PWM duty cycle
+VAR(pwm_max_duty,    md, f32,   0,      1, 1) // Maximum PWM duty cycle
+VAR(pwm_duty,        pd, f32,   0,      0, 1) // Current PWM duty cycle
+VAR(pwm_freq,        sf, u16,   0,      1, 1) // Spindle PWM frequency in Hz
 
 // Modbus spindle
-VAR(modbus_debug,     hb, b8,    0,      1, 1, "Modbus debugging")
-VAR(modbus_id,        hi, u8,    0,      1, 1, "Modbus ID")
-VAR(modbus_baud,      mb, u8,    0,      1, 1, "Modbus BAUD rate")
-VAR(modbus_parity,    ma, u8,    0,      1, 1, "Modbus parity")
-VAR(modbus_stop,      ms, u8,    0,      1, 1, "Modbus stop bits")
-VAR(modbus_connected, he, b8,    0,      0, 1, "Modbus connected")
+VAR(modbus_debug,    hb, b8,    0,      1, 1) // Modbus debugging
+VAR(modbus_id,       hi, u8,    0,      1, 1) // Modbus ID
+VAR(modbus_baud,     mb, u8,    0,      1, 1) // Modbus BAUD rate
+VAR(modbus_parity,   ma, u8,    0,      1, 1) // Modbus parity
+VAR(modbus_status,   mx, u8,    0,      0, 1) // Modbus status
+VAR(modbus_response, mr, u16,   0,      0, 1) // Modbus read response
+
+// VFD spindle
+VAR(vfd_max_freq,    vf, u16,   0,      1, 1) // VFD maximum frequency
+VAR(vfd_reg_type,    vt, u8,    VFDREG, 1, 1) // VFD register type
+VAR(vfd_reg_addr,    va, u16,   VFDREG, 1, 1) // VFD register address
+VAR(vfd_reg_val,     vv, u16,   VFDREG, 1, 1) // VFD register value
 
 // Huanyang spindle
-VAR(hy_freq,         hz, f32,   0,      0, 1, "Huanyang actual freq")
-VAR(hy_current,      hc, f32,   0,      0, 1, "Huanyang actual current")
-VAR(hy_temp,         ht, u16,   0,      0, 1, "Huanyang temperature")
-VAR(hy_max_freq,     hx, f32,   0,      0, 1, "Huanyang max freq")
-VAR(hy_min_freq,     hm, f32,   0,      0, 1, "Huanyang min freq")
-VAR(hy_rated_rpm,    hq, u16,   0,      0, 1, "Huanyang rated RPM")
-VAR(hy_status,       hs, u8,    0,      0, 1, "Huanyang status flags")
+VAR(hy_freq,         hz, f32,   0,      0, 1) // Huanyang actual freq
+VAR(hy_current,      hc, f32,   0,      0, 1) // Huanyang actual current
+VAR(hy_temp,         ht, u16,   0,      0, 1) // Huanyang temperature
+VAR(hy_max_freq,     hx, f32,   0,      0, 1) // Huanyang max freq
+VAR(hy_min_freq,     hm, f32,   0,      0, 1) // Huanyang min freq
+VAR(hy_rated_rpm,    hq, u16,   0,      0, 1) // Huanyang rated RPM
+VAR(hy_status,       hs, u8,    0,      0, 1) // Huanyang status flags
 
 // Machine state
-VAR(id,              id, u32,   0,      1, 1, "Last executed command ID")
-VAR(feed_override,   fo, f32,   0,      1, 1, "Feed rate override")
-VAR(speed_override,  so, f32,   0,      1, 1, "Spindle speed override")
-VAR(optional_pause,  op, b8,    0,      1, 1, "Optional pause state")
+VAR(id,              id, u32,   0,      1, 1) // Last executed command ID
+VAR(feed_override,   fo, u16,   0,      1, 1) // Feed rate override
+VAR(speed_override,  so, u16,   0,      1, 1) // Spindle speed override
+VAR(optional_pause,  op, b8,    0,      1, 1) // Optional pause state
 
 // System
-VAR(velocity,         v, f32,   0,      0, 1, "Current velocity")
-VAR(acceleration,    ax, f32,   0,      0, 1, "Current acceleration")
-VAR(jerk,             j, f32,   0,      0, 1, "Current jerk")
-VAR(peak_vel,        pv, f32,   0,      1, 1, "Peak velocity, set to clear")
-VAR(peak_accel,      pa, f32,   0,      1, 1, "Peak acceleration, set to clear")
-VAR(hw_id,          hid, str,   0,      0, 1, "Hardware ID")
-VAR(estop,           es, b8,    0,      1, 1, "Emergency stop")
-VAR(estop_reason,    er, pstr,  0,      0, 1, "Emergency stop reason")
-VAR(state,           xx, pstr,  0,      0, 1, "Machine state")
-VAR(hold_reason,     pr, pstr,  0,      0, 1, "Machine pause reason")
-VAR(underflow,       un, u32,   0,      0, 1, "Stepper underflow count")
-VAR(dwell_time,      dt, f32,   0,      0, 1, "Dwell timer")
+VAR(velocity,         v, f32,   0,      0, 1) // Current velocity
+VAR(acceleration,    ax, f32,   0,      0, 1) // Current acceleration
+VAR(jerk,             j, f32,   0,      0, 1) // Current jerk
+VAR(peak_vel,        pv, f32,   0,      1, 1) // Peak velocity, set to clear
+VAR(peak_accel,      pa, f32,   0,      1, 1) // Peak accel, set to clear
+VAR(hw_id,          hid, str,   0,      0, 1) // Hardware ID
+VAR(estop,           es, b8,    0,      1, 1) // Emergency stop
+VAR(estop_reason,    er, pstr,  0,      0, 1) // Emergency stop reason
+VAR(state,           xx, pstr,  0,      0, 1) // Machine state
+VAR(hold_reason,     pr, pstr,  0,      0, 1) // Machine pause reason
+VAR(underflow,       un, u32,   0,      0, 1) // Stepper underflow count
+VAR(dwell_time,      dt, f32,   0,      0, 1) // Dwell timer
index b6ceffbd6ee4c1fb54ed3bef970c300087e77076..949f5aa50aab772fd5359159e393464d16d25813 100644 (file)
@@ -42,5 +42,4 @@ void vars_report_all(bool enable);
 void vars_report_var(const char *code, bool enable);
 stat_t vars_print(const char *name);
 stat_t vars_set(const char *name, const char *value);
-float vars_get_number(const char *name);
 void vars_print_json();
index 03195c7144fbc7acb1e732ea8a38d77c5a006084..267e916162f6e2482fe59e57986173f4bf1425b5 100644 (file)
@@ -1,13 +1,12 @@
 #include "cpp_magic.h"
 {
-#define VAR(NAME, CODE, TYPE, INDEX, SET, REPORT, HELP) \
+#define VAR(NAME, CODE, TYPE, INDEX, SET, REPORT) \
 #CODE: {                                        \
     "name": #NAME,                              \
     "type": #TYPE,                              \
     "index": IF_ELSE(INDEX)(true, false),       \
     "setable": IF_ELSE(SET)(true, false),       \
-    "report": IF_ELSE(REPORT)(true, false),     \
-    "help": HELP                                \
+    "report": IF_ELSE(REPORT)(true, false)      \
   },
 #include "vars.def"
 #undef VAR
diff --git a/src/avr/src/vfd/huanyang.c b/src/avr/src/vfd/huanyang.c
deleted file mode 100644 (file)
index 259c006..0000000
+++ /dev/null
@@ -1,331 +0,0 @@
-/******************************************************************************\
-
-                 This file is part of the Buildbotics firmware.
-
-                   Copyright (c) 2015 - 2018, Buildbotics LLC
-                              All rights reserved.
-
-      This file ("the software") is free software: you can redistribute it
-      and/or modify it under the terms of the GNU General Public License,
-       version 2 as published by the Free Software Foundation. You should
-       have received a copy of the GNU General Public License, version 2
-      along with the software. If not, see <http://www.gnu.org/licenses/>.
-
-      The software is distributed in the hope that it will be useful, but
-           WITHOUT ANY WARRANTY; without even the implied warranty of
-       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
-                Lesser General Public License for more details.
-
-        You should have received a copy of the GNU Lesser General Public
-                 License along with the software.  If not, see
-                        <http://www.gnu.org/licenses/>.
-
-                 For information regarding this software email:
-                   "Joseph Coffland" <joseph@buildbotics.com>
-
-\******************************************************************************/
-
-#include "huanyang.h"
-#include "config.h"
-#include "modbus.h"
-#include "report.h"
-
-#include <string.h>
-#include <math.h>
-
-
-/*
-  Huanyang is not quite Modbus compliant.
-
-  Message format is:
-
-    [id][func][length][data][checksum]
-
-  Where:
-
-     id       - 1-byte Peer ID
-     func     - 1-byte One of hy_func_t
-     length   - 1-byte Length data in bytes
-     data     - length bytes - Command arguments
-     checksum - 16-bit CRC: x^16 + x^15 + x^2 + 1 (0xa001) initial: 0xffff
-*/
-
-
-// See VFD manual pg56 3.1.3
-typedef enum {
-  HUANYANG_FUNC_READ = 1, // [len=1][hy_addr_t]
-  HUANYANG_FUNC_WRITE,    // [len=3][hy_addr_t][data]
-  HUANYANG_CTRL_WRITE,    // [len=1][hy_ctrl_state_t]
-  HUANYANG_CTRL_READ,     // [len=1][hy_ctrl_addr_t]
-  HUANYANG_FREQ_WRITE,    // [len=2][freq]
-  HUANYANG_RESERVED_1,
-  HUANYANG_RESERVED_2,
-  HUANYANG_LOOP_TEST,
-} hy_func_t;
-
-
-// Sent in HUANYANG_CTRL_WRITE
-// See VFD manual pg57 3.1.3.c
-typedef enum {
-  HUANYANG_RUN         = 1 << 0,
-  HUANYANG_FORWARD     = 1 << 1,
-  HUANYANG_REVERSE     = 1 << 2,
-  HUANYANG_STOP        = 1 << 3,
-  HUANYANG_REV_FWD     = 1 << 4,
-  HUANYANG_JOG         = 1 << 5,
-  HUANYANG_JOG_FORWARD = 1 << 6,
-  HUANYANG_JOG_REVERSE = 1 << 7,
-} hy_ctrl_state_t;
-
-
-// Returned by HUANYANG_CTRL_WRITE
-// See VFD manual pg57 3.1.3.c
-typedef enum {
-  HUANYANG_STATUS_RUN         = 1 << 0,
-  HUANYANG_STATUS_JOG         = 1 << 1,
-  HUANYANG_STATUS_COMMAND_REV = 1 << 2,
-  HUANYANG_STATUS_RUNNING     = 1 << 3,
-  HUANYANG_STATUS_JOGGING     = 1 << 4,
-  HUANYANG_STATUS_JOGGING_REV = 1 << 5,
-  HUANYANG_STATUS_BRAKING     = 1 << 6,
-  HUANYANG_STATUS_TRACK_START = 1 << 7,
-} hy_ctrl_status_t;
-
-
-// Sent in HUANYANG_CTRL_READ
-// See VFD manual pg57 3.1.3.d
-typedef enum {
-  HUANYANG_TARGET_FREQ,
-  HUANYANG_ACTUAL_FREQ,
-  HUANYANG_ACTUAL_CURRENT,
-  HUANYANG_ACTUAL_RPM,
-  HUANYANG_DCV,
-  HUANYANG_ACV,
-  HUANYANG_COUNTER,
-  HUANYANG_TEMPERATURE,
-} hy_ctrl_addr_t;
-
-
-static struct {
-  uint8_t state;
-  hy_func_t func;
-  uint8_t data[4];
-  uint8_t bytes;
-  uint8_t response;
-
-  bool shutdown;
-  bool changed;
-  float speed;
-
-  float actual_freq;
-  float actual_current;
-  uint16_t actual_rpm;
-  uint16_t temperature;
-
-  float max_freq;
-  float min_freq;
-  uint16_t rated_rpm;
-
-  uint8_t status;
-} hy = {0};
-
-
-static void _func_read(hy_addr_t addr) {
-  hy.func     = HUANYANG_FUNC_READ;
-  hy.bytes    = 2;
-  hy.response = 4;
-  hy.data[0]  = 1;
-  hy.data[1]  = addr;
-}
-
-
-static void _ctrl_write(hy_ctrl_state_t state) {
-  hy.func     = HUANYANG_CTRL_WRITE;
-  hy.bytes    = 2;
-  hy.response = 2;
-  hy.data[0]  = 1;
-  hy.data[1]  = state;
-}
-
-
-static void _ctrl_read(hy_ctrl_addr_t addr) {
-  hy.func     = HUANYANG_CTRL_READ;
-  hy.bytes    = 2;
-  hy.response = 4;
-  hy.data[0]  = 1;
-  hy.data[1]  = addr;
-}
-
-
-static void _freq_write(uint16_t freq) {
-  hy.func     = HUANYANG_FREQ_WRITE;
-  hy.bytes    = 3;
-  hy.response = 3;
-  hy.data[0]  = 2;
-  hy.data[1]  = freq >> 8;
-  hy.data[2]  = freq;
-}
-
-
-static void _func_read_response(hy_addr_t addr, uint16_t value) {
-  switch (addr) {
-  case HY_PD005_MAX_FREQUENCY:         hy.max_freq  = value * 0.01; break;
-  case HY_PD011_FREQUENCY_LOWER_LIMIT: hy.min_freq  = value * 0.01; break;
-  case HY_PD144_RATED_MOTOR_RPM:       hy.rated_rpm = value;        break;
-  default: break;
-  }
-}
-
-
-static void _ctrl_read_response(hy_ctrl_addr_t addr, uint16_t value) {
-  switch (addr) {
-  case HUANYANG_ACTUAL_FREQ:    hy.actual_freq    = value * 0.01; break;
-  case HUANYANG_ACTUAL_CURRENT: hy.actual_current = value * 0.01; break;
-  case HUANYANG_ACTUAL_RPM:     hy.actual_rpm     = value;        break;
-  case HUANYANG_TEMPERATURE:    hy.temperature    = value;        break;
-  default: break;
-  }
-}
-
-
-static uint16_t _read_word(const uint8_t *data) {
-  return (uint16_t)data[0] << 8 | data[1];
-}
-
-
-static void _handle_response(hy_func_t func, const uint8_t *data) {
-  switch (func) {
-  case HUANYANG_FUNC_READ:
-    _func_read_response((hy_addr_t)*data, _read_word(data + 1));
-    break;
-
-  case HUANYANG_FUNC_WRITE: break;
-  case HUANYANG_CTRL_WRITE: hy.status = *data; break;
-
-  case HUANYANG_CTRL_READ:
-    _ctrl_read_response((hy_ctrl_addr_t)*data, _read_word(data + 1));
-    break;
-
-  case HUANYANG_FREQ_WRITE: break;
-  default: break;
-  }
-}
-
-
-static void _next_command();
-
-
-static void _reset(bool halt) {
-  // Save settings
-  float speed = hy.speed;
-
-  // Clear state
-  memset(&hy, 0, sizeof(hy));
-
-  // Restore settings
-  hy.speed = speed;
-  hy.changed = true;
-
-  if (!halt) _next_command();
-}
-
-
-static void _modbus_cb(uint8_t func, uint8_t bytes, const uint8_t *data) {
-  if (!data) _reset(true);
-
-  else if (bytes == *data + 1) {
-    _handle_response((hy_func_t)func, data + 1);
-
-    if (func == HUANYANG_CTRL_WRITE && hy.shutdown) {
-      _reset(true);
-      modbus_deinit();
-      return;
-    }
-
-    // Next command
-    if (++hy.state == 9) {
-      hy.state = 5;
-      report_request();
-    }
-
-    // Update freq
-    if (hy.shutdown || (hy.changed && 4 < hy.state)) hy.state = 0;
-  }
-
-  _next_command();
-}
-
-
-static void _next_command() {
-  switch (hy.state) {
-  case 0: { // Update direction
-    hy_ctrl_state_t state = HUANYANG_STOP;
-    if (!hy.shutdown) {
-      if (0 < hy.speed)
-        state = (hy_ctrl_state_t)(HUANYANG_RUN | HUANYANG_FORWARD);
-      else if (hy.speed < 0)
-        state = (hy_ctrl_state_t)(HUANYANG_RUN | HUANYANG_REV_FWD);
-    }
-
-    _ctrl_write(state);
-    break;
-  }
-
-  case 1: _func_read(HY_PD005_MAX_FREQUENCY); break;
-  case 2: _func_read(HY_PD011_FREQUENCY_LOWER_LIMIT); break;
-  case 3: _func_read(HY_PD144_RATED_MOTOR_RPM); break;
-
-  case 4: { // Update freqency
-    // Compute frequency in Hz
-    float freq = fabs(hy.speed * hy.max_freq);
-
-    // Frequency write command
-    _freq_write(freq * 100);
-    hy.changed = false;
-    break;
-  }
-
-  case 5: _ctrl_read(HUANYANG_ACTUAL_FREQ);    break;
-  case 6: _ctrl_read(HUANYANG_ACTUAL_CURRENT); break;
-  case 7: _ctrl_read(HUANYANG_ACTUAL_RPM);     break;
-  case 8: _ctrl_read(HUANYANG_TEMPERATURE);    break;
-  }
-
-  // Send command
-  modbus_func(hy.func, hy.bytes, hy.data, hy.response, _modbus_cb);
-}
-
-
-void huanyang_init() {
-  modbus_init();
-  _reset(false);
-}
-
-
-void huanyang_deinit() {hy.shutdown = true;}
-
-
-void huanyang_set(float speed) {
-  if (hy.speed != speed) {
-    hy.speed = speed;
-    hy.changed = true;
-  }
-}
-
-
-float huanyang_get() {return hy.actual_freq / hy.max_freq;}
-
-
-void huanyang_stop() {
-  huanyang_set(0);
-  _reset(false);
-}
-
-
-float get_hy_freq() {return hy.actual_freq;}
-float get_hy_current() {return hy.actual_current;}
-uint16_t get_hy_temp() {return hy.temperature;}
-float get_hy_max_freq() {return hy.max_freq;}
-float get_hy_min_freq() {return hy.min_freq;}
-uint16_t get_hy_rated_rpm() {return hy.rated_rpm;}
-float get_hy_status() {return hy.status;}
diff --git a/src/avr/src/vfd/huanyang.h b/src/avr/src/vfd/huanyang.h
deleted file mode 100644 (file)
index c5b88af..0000000
+++ /dev/null
@@ -1,224 +0,0 @@
-/******************************************************************************\
-
-                 This file is part of the Buildbotics firmware.
-
-                   Copyright (c) 2015 - 2018, Buildbotics LLC
-                              All rights reserved.
-
-      This file ("the software") is free software: you can redistribute it
-      and/or modify it under the terms of the GNU General Public License,
-       version 2 as published by the Free Software Foundation. You should
-       have received a copy of the GNU General Public License, version 2
-      along with the software. If not, see <http://www.gnu.org/licenses/>.
-
-      The software is distributed in the hope that it will be useful, but
-           WITHOUT ANY WARRANTY; without even the implied warranty of
-       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
-                Lesser General Public License for more details.
-
-        You should have received a copy of the GNU Lesser General Public
-                 License along with the software.  If not, see
-                        <http://www.gnu.org/licenses/>.
-
-                 For information regarding this software email:
-                   "Joseph Coffland" <joseph@buildbotics.com>
-
-\******************************************************************************/
-
-#pragma once
-
-
-void huanyang_init();
-void huanyang_deinit();
-void huanyang_set(float speed);
-float huanyang_get();
-void huanyang_stop();
-
-
-/// See Huanyang VFD user manual
-typedef enum {
-  HY_PD000_PARAMETER_LOCK,
-  HY_PD001_SOURCE_OF_OPERATION_COMMANDS,
-  HY_PD002_SOURCE_OF_OPERATING_FREQUENCY,
-  HY_PD003_MAIN_FREQUENCY,
-  HY_PD004_BASE_FREQUENCY,
-  HY_PD005_MAX_FREQUENCY,
-  HY_PD006_INTERMEDIATE_FREQUENCY,
-  HY_PD007_MIN_FREQUENCY,
-  HY_PD008_MAX_VOLTAGE,
-  HY_PD009_INTERMEDIATE_VOLTAGE,
-  HY_PD010_MIN_VOLTAGE,
-  HY_PD011_FREQUENCY_LOWER_LIMIT,
-  HY_PD012_RESERVED,
-  HY_PD013_PARAMETER_RESET,
-  HY_PD014_ACCEL_TIME_1,
-  HY_PD015_DECEL_TIME_1,
-  HY_PD016_ACCEL_TIME_2,
-  HY_PD017_DECEL_TIME_2,
-  HY_PD018_ACCEL_TIME_3,
-  HY_PD019_DECEL_TIME_3,
-  HY_PD020_ACCEL_TIME_4,
-  HY_PD021_DECEL_TIME_4,
-  HY_PD022_FACTORY_RESERVED,
-  HY_PD023_REV_ROTATION_SELECT,
-  HY_PD024_STOP_KEY,
-  HY_PD025_STARTING_MODE,
-  HY_PD026_STOPPING_MODE,
-  HY_PD027_STARTING_FREQUENCY,
-  HY_PD028_STOPPING_FREQUENCY,
-  HY_PD029_DC_BRAKING_TIME_AT_START,
-  HY_PD030_DC_BRAKING_TIME_AT_STOP,
-  HY_PD031_DC_BRAKING_VOLTAGE_LEVEL,
-  HY_PD032_FREQUENCY_TRACK_TIME,
-  HY_PD033_CURRENT_LEVEL_FOR_FREQUENCY_TRACK,
-  HY_PD034_VOLTAGE_RISE_TIME_FOR_FREQUENCY_TRACK,
-  HY_PD035_FREQUENCY_STEP_LENGTH,
-  HY_PD036,
-  HY_PD037,
-  HY_PD038,
-  HY_PD039,
-  HY_PD040,
-  HY_PD041_CARRIER_FREQUENCY,
-  HY_PD042_JOGGING_FREQUENCY,
-  HY_PD043_S_CURVE_TIME,
-  HY_PD044_MULTI_INPUT_FOR,
-  HY_PD045_MULTI_INPUT_REV,
-  HY_PD046_MULTI_INPUT_RST,
-  HY_PD047_MULTI_INPUT_SPH,
-  HY_PD048_MULTI_INPUT_SPM,
-  HY_PD049_MULTI_INPUT_SPL,
-  HY_PD050_MULTI_OUTPUT_DRV,
-  HY_PD051_MULTI_OUTPUT_UPF,
-  HY_PD052_MULTI_OUTPUT_FA_FB_FC,
-  HY_PD053_MULTI_OUTPUT_KA_KB,
-  HY_PD054_MULTI_OUTPUT_AM,
-  HY_PD055_AM_ANALOG_OUTPUT_GAIN,
-  HY_PD056_SKIP_FREQUENCY_1,
-  HY_PD057_SKIP_FREQUENCY_2,
-  HY_PD058_SKIP_FREQUENCY_3,
-  HY_PD059_SKIP_FREQUENCY_RANGE,
-  HY_PD060_UNIFORM_FREQUENCY_1,
-  HY_PD061_UNIFORM_FREQUENCY_2,
-  HY_PD062_UNIFORM_FREQUENCY_RANGE,
-  HY_PD063_TIMER_1_TIME,
-  HY_PD064_TIMER_2_TIME,
-  HY_PD065_COUNTING_VALUE,
-  HY_PD066_INTERMEDIATE_COUNTER,
-  HY_PD067,
-  HY_PD068,
-  HY_PD069,
-  HY_PD070_ANALOG_INPUT,
-  HY_PD071_ANALOG_FILTERING_CONSTANT,
-  HY_PD072_HIGHER_ANALOG_FREQUENCY,
-  HY_PD073_LOWER_ANALOG_FREQUENCY,
-  HY_PD074_BIAS_DIRECTION_AT_HIGHER_FREQUENCY,
-  HY_PD075_BIAS_DIRECTION_AT_LOWER_FREQUENCY,
-  HY_PD076_ANALOG_NEGATIVE_BIAS_REVERSE,
-  HY_PD077_UP_DOWN_FUNCTION,
-  HY_PD078_UP_DOWN_SPEED,
-  HY_PD079,
-  HY_PD080_PLC_OPERATION,
-  HY_PD081_AUTO_PLC,
-  HY_PD082_PLC_RUNNING_DIRECTION,
-  HY_PD083,
-  HY_PD084_PLC_RAMP_TIME,
-  HY_PD085,
-  HY_PD086_FREQUENCY_2,
-  HY_PD087_FREQUENCY_3,
-  HY_PD088_FREQUENCY_4,
-  HY_PD089_FREQUENCY_5,
-  HY_PD090_FREQUENCY_6,
-  HY_PD091_FREQUENCY_7,
-  HY_PD092_FREQUENCY_8,
-  HY_PD093,
-  HY_PD094,
-  HY_PD095,
-  HY_PD096,
-  HY_PD097,
-  HY_PD098,
-  HY_PD099,
-  HY_PD100,
-  HY_PD101_TIMER_1,
-  HY_PD102_TIMER_2,
-  HY_PD103_TIMER_3,
-  HY_PD104_TIMER_4,
-  HY_PD105_TIMER_5,
-  HY_PD106_TIMER_6,
-  HY_PD107_TIMER_7,
-  HY_PD108_TIMER_8,
-  HY_PD109,
-  HY_PD110,
-  HY_PD111,
-  HY_PD112,
-  HY_PD113,
-  HY_PD114,
-  HY_PD115,
-  HY_PD116,
-  HY_PD117_AUTOPLC_MEMORY_FUNCTION,
-  HY_PD118_OVER_VOLTAGE_STALL_PREVENTION,
-  HY_PD119_STALL_PREVENTION_LEVEL_AT_RAMP_UP,
-  HY_PD120_STALL_PREVENTION_LEVEL_AT_CONSTANT_SPEED,
-  HY_PD121_DECEL_TIME_FOR_STALL_PREVENTION_AT_CONSTANT_SPEED,
-  HY_PD122_STALL_PREVENTION_LEVEL_AT_DECELERATION,
-  HY_PD123_OVER_TORQUE_DETECT_MODE,
-  HY_PD124_OVER_TORQUE_DETECT_LEVEL,
-  HY_PD125_OVER_TORQUE_DETECT_TIME,
-  HY_PD126,
-  HY_PD127,
-  HY_PD128,
-  HY_PD129,
-  HY_PD130_NUMBER_OF_AUXILIARY_PUMP,
-  HY_PD131_CONTINUOUS_RUNNING_TIME_OF_AUXILIARY_PUMPS,
-  HY_PD132_INTERLOCKING_TIME_OF_AUXILIARY_PUMP,
-  HY_PD133_HIGH_SPEED_RUNNING_TIME,
-  HY_PD134_LOW_SPEED_RUNNING_TIME,
-  HY_PD135_STOPPING_VOLTAGE_LEVEL,
-  HY_PD136_LASTING_TIME_OF_STOPPING_VOLTAGE_LEVEL,
-  HY_PD137_WAKEUP_VOLTAGE_LEVEL,
-  HY_PD138_SLEEP_FREQUENCY,
-  HY_PD139_LASTING_TIME_OF_SLEEP_FREQUENCY,
-  HY_PD140,
-  HY_PD141_RATED_MOTOR_VOLTAGE,
-  HY_PD142_RATED_MOTOR_CURRENT,
-  HY_PD143_MOTOR_POLE_NUMBER,
-  HY_PD144_RATED_MOTOR_RPM,
-  HY_PD145_AUTO_TORQUE_COMPENSATION,
-  HY_PD146_MOTOR_NO_LOAD_CURRENT,
-  HY_PD147_MOTOR_SLIP_COMPENSATION,
-  HY_PD148,
-  HY_PD149,
-  HY_PD150_AUTO_VOLTAGE_REGULATION,
-  HY_PD151_AUTO_ENERGY_SAVING,
-  HY_PD152_FAULT_RESTART_TIME,
-  HY_PD153_RESTART_AFTER_INSTANTANEOUS_STOP,
-  HY_PD154_ALLOWABLE_POWER_BREAKDOWN_TIME,
-  HY_PD155_NUMBER_OF_ABNORMAL_RESTART,
-  HY_PD156_PROPORTIONAL_CONSTANT,
-  HY_PD157_INTEGRAL_TIME,
-  HY_PD158_DIFFERENTIAL_TIME,
-  HY_PD159_TARGET_VALUE,
-  HY_PD160_PID_TARGET_VALUE,
-  HY_PD161_PID_UPPER_LIMIT,
-  HY_PD162_PID_LOWER_LIMIT,
-  HY_PD163_COMMUNICATION_ADDRESSES,
-  HY_PD164_COMMUNICATION_BAUD_RATE,
-  HY_PD165_COMMUNICATION_DATA_METHOD,
-  HY_PD166,
-  HY_PD167,
-  HY_PD168,
-  HY_PD169,
-  HY_PD170_DISPLAY_ITEMS,
-  HY_PD171_DISPLAY_ITEMS_OPEN,
-  HY_PD172_FAULT_CLEAR,
-  HY_PD173,
-  HY_PD174_RATED_CURRENT_OF_INVERTER,
-  HY_PD175_INVERTER_MODEL,
-  HY_PD176_INVERTER_FREQUENCY_STANDARD,
-  HY_PD177_FAULT_RECORD_1,
-  HY_PD178_FAULT_RECORD_2,
-  HY_PD179_FAULT_RECORD_3,
-  HY_PD180_FAULT_RECORD_4,
-  HY_PD181_SOFTWARE_VERSION,
-  HY_PD182_MANUFACTURE_DATE,
-  HY_PD183_SERIAL_NO,
-} hy_addr_t;
diff --git a/src/avr/src/vfd/yl600.c b/src/avr/src/vfd/yl600.c
deleted file mode 100644 (file)
index e91e901..0000000
+++ /dev/null
@@ -1,128 +0,0 @@
-/******************************************************************************\
-
-                 This file is part of the Buildbotics firmware.
-
-                   Copyright (c) 2015 - 2018, Buildbotics LLC
-                              All rights reserved.
-
-      This file ("the software") is free software: you can redistribute it
-      and/or modify it under the terms of the GNU General Public License,
-       version 2 as published by the Free Software Foundation. You should
-       have received a copy of the GNU General Public License, version 2
-      along with the software. If not, see <http://www.gnu.org/licenses/>.
-
-      The software is distributed in the hope that it will be useful, but
-           WITHOUT ANY WARRANTY; without even the implied warranty of
-       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
-                Lesser General Public License for more details.
-
-        You should have received a copy of the GNU Lesser General Public
-                 License along with the software.  If not, see
-                        <http://www.gnu.org/licenses/>.
-
-                 For information regarding this software email:
-                   "Joseph Coffland" <joseph@buildbotics.com>
-
-\******************************************************************************/
-
-
-#include "modbus.h"
-
-#include <math.h>
-
-
-#define P(H, L) ((H) << 8 | (L))
-
-
-enum {
-  P00_00_MAIN_FREQ          = P(0, 0),
-  P00_01_START_STOP_SOURCE  = P(0, 1),
-  P00_04_HIGEST_OUTPUT_FREQ = P(0, 4),
-  P01_00_DIRECTION          = P(1, 0),
-  P07_00_FREQ_1             = P(7, 0),
-  P07_08_FREQ_SOURCE_1      = P(7, 8),
-};
-
-
-static struct {
-  uint8_t state;
-  bool changed;
-  bool shutdown;
-
-  float speed;
-  uint16_t max_freq;
-  float actual_speed;
-} s = {0};
-
-
-static void _next_command();
-
-
-static uint16_t _speed2freq(float speed) {return fabs(speed) * s.max_freq;}
-static float _freq2speed(uint16_t freq) {return (float)freq / s.max_freq;}
-
-
-static void _next_state(bool ok) {
-  if (!ok) s.state = 0;
-
-  else if (s.changed) {
-    s.changed = false;
-    s.state = 0;
-
-  } else if (++s.state == 5) s.state = 4;
-
-  _next_command();
-}
-
-
-static void _read_cb(bool ok, uint16_t addr, uint16_t value) {
-  if (ok)
-    switch (addr) {
-    case P00_04_HIGEST_OUTPUT_FREQ: s.max_freq = value; break;
-    case P07_00_FREQ_1: s.actual_speed = _freq2speed(value); break;
-    }
-
-  _next_state(ok);
-}
-
-
-static void _write_cb(bool ok, uint16_t addr) {_next_state(ok);}
-
-
-static void _next_command() {
-  if (s.shutdown) {
-    modbus_deinit();
-    return;
-  }
-
-  // TODO spin direction
-  switch (s.state) {
-  case 0: modbus_read(P00_04_HIGEST_OUTPUT_FREQ, _read_cb); break;
-  case 1: modbus_write(P00_01_START_STOP_SOURCE, 1, _write_cb); break;
-  case 2: modbus_write(P07_08_FREQ_SOURCE_1, 1, _write_cb); break;
-  case 3: modbus_write(P07_00_FREQ_1, _speed2freq(s.speed), _write_cb); break;
-  case 4: modbus_read(P07_00_FREQ_1, _read_cb); break;
-  }
-}
-
-
-void yl600_init() {
-  modbus_init();
-  s.shutdown = false;
-  _next_command();
-}
-
-
-void yl600_deinit() {s.shutdown = true;}
-
-
-void yl600_set(float speed) {
-  if (s.speed != speed) {
-    s.speed = speed;
-    s.changed = true;
-  }
-}
-
-
-float yl600_get() {return s.actual_speed;}
-void yl600_stop() {yl600_set(0);}
diff --git a/src/avr/src/vfd_spindle.c b/src/avr/src/vfd_spindle.c
new file mode 100644 (file)
index 0000000..ddfc790
--- /dev/null
@@ -0,0 +1,346 @@
+/******************************************************************************\
+
+                 This file is part of the Buildbotics firmware.
+
+                   Copyright (c) 2015 - 2018, Buildbotics LLC
+                              All rights reserved.
+
+      This file ("the software") is free software: you can redistribute it
+      and/or modify it under the terms of the GNU General Public License,
+       version 2 as published by the Free Software Foundation. You should
+       have received a copy of the GNU General Public License, version 2
+      along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+      The software is distributed in the hope that it will be useful, but
+           WITHOUT ANY WARRANTY; without even the implied warranty of
+       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+                Lesser General Public License for more details.
+
+        You should have received a copy of the GNU Lesser General Public
+                 License along with the software.  If not, see
+                        <http://www.gnu.org/licenses/>.
+
+                 For information regarding this software email:
+                   "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#include "vfd_spindle.h"
+#include "modbus.h"
+#include "rtc.h"
+#include "config.h"
+#include "pgmspace.h"
+
+#include <string.h>
+#include <math.h>
+#include <stdint.h>
+
+
+typedef enum {
+  REG_DISABLED,
+
+  REG_CONNECT_WRITE,
+
+  REG_MAX_FREQ_READ,
+  REG_MAX_FREQ_FIXED,
+
+  REG_FREQ_SET,
+  REG_FREQ_SIGN_SET,
+
+  REG_STOP_WRITE,
+  REG_FWD_WRITE,
+  REG_REV_WRITE,
+
+  REG_FREQ_READ,
+  REG_FREQ_SIGN_READ,
+
+  REG_DISCONNECT_WRITE,
+} vfd_reg_type_t;
+
+
+typedef struct {
+  vfd_reg_type_t type;
+  uint16_t addr;
+  uint16_t value;
+} vfd_reg_t;
+
+
+#define P(H, L) ((H) << 8 | (L))
+
+
+const vfd_reg_t yl600_regs[] PROGMEM = {
+  {REG_CONNECT_WRITE,    P(7, 8), 1}, // P07_08_FREQ_SOURCE_1
+  {REG_CONNECT_WRITE,    P(0, 1), 1}, // P00_01_START_STOP_SOURCE
+  {REG_MAX_FREQ_READ,    P(0, 4), 0}, // P00_04_HIGEST_OUTPUT_FREQ
+  {REG_FREQ_SET,         P(7, 0), 0}, // P07_00_FREQ_1
+//  {REG_STOP_WRITE,       P(?, ?), ?}, //
+//  {REG_FWD_WRITE,        P(1, 0), ?}, // P01_00_DIRECTION
+//  {REG_REV_WRITE,        P(?, ?), ?}, //
+  {REG_FREQ_READ,        P(0, 0), 0}, // P00_00_MAIN_FREQ
+  {REG_DISCONNECT_WRITE, P(0, 1), 0}, // P00_01_START_STOP_SOURCE
+  {REG_DISCONNECT_WRITE, P(7, 8), 0}, // P07_08_FREQ_SOURCE_1
+  {REG_DISABLED},
+};
+
+
+// NOTE, Modbus reg = AC Tech reg + 1
+const vfd_reg_t ac_tech_regs[] PROGMEM = {
+  {REG_CONNECT_WRITE,    49,   19}, // Password unlock
+  {REG_CONNECT_WRITE,     2,  512}, // Manual mode
+  {REG_MAX_FREQ_READ,    63,    0}, // Max frequency
+  {REG_FREQ_SET,         41,    0}, // Frequency
+  {REG_STOP_WRITE,        2,    4}, // Stop drive
+  {REG_FWD_WRITE,         2,  128}, // Forward
+  {REG_FWD_WRITE,         2,    8}, // Start drive
+  {REG_REV_WRITE,         2,   64}, // Reverse
+  {REG_REV_WRITE,         2,    8}, // Start drive
+  {REG_FREQ_READ,        26,    0}, // Actual speed
+  {REG_DISCONNECT_WRITE,  2,    2}, // Lock controls and parameters
+  {REG_DISABLED},
+};
+
+
+static vfd_reg_t regs[VFDREG];
+static vfd_reg_t custom_regs[VFDREG];
+
+static struct {
+  vfd_reg_type_t state;
+  int8_t reg;
+  bool changed;
+  bool shutdown;
+
+  float speed;
+  uint16_t max_freq;
+  float actual_speed;
+
+  uint32_t wait;
+  deinit_cb_t deinit_cb;
+} vfd;
+
+
+static void _disconnected() {
+  modbus_deinit();
+  if (vfd.deinit_cb) vfd.deinit_cb();
+  vfd.deinit_cb = 0;
+}
+
+
+static bool _next_state() {
+  switch (vfd.state) {
+  case REG_FREQ_SIGN_SET:
+    if (vfd.speed < 0) vfd.state = REG_REV_WRITE;
+    else if (0 < vfd.speed) vfd.state = REG_FWD_WRITE;
+    else vfd.state = REG_STOP_WRITE;
+    break;
+
+  case REG_STOP_WRITE: case REG_FWD_WRITE: case REG_REV_WRITE:
+    vfd.state = REG_FREQ_READ;
+    break;
+
+  case REG_FREQ_SIGN_READ:
+    if (vfd.shutdown) vfd.state = REG_DISCONNECT_WRITE;
+
+    else if (vfd.changed) {
+      // Update frequency and state
+      vfd.changed = false;
+      vfd.state = REG_MAX_FREQ_READ;
+
+    } else {
+      // Continue querying after delay
+      vfd.state = REG_FREQ_READ;
+      vfd.wait = rtc_get_time() + VFD_QUERY_DELAY;
+      return false;
+    }
+    break;
+
+  case REG_DISCONNECT_WRITE:
+    _disconnected();
+    return false;
+
+  default:
+    vfd.state = (vfd_reg_type_t)(vfd.state + 1);
+  }
+
+  return true;
+}
+
+
+static bool _exec_command();
+
+
+static void _next_reg() {
+  while (true) {
+    vfd.reg++;
+
+    if (vfd.reg == VFDREG) {
+      vfd.reg = -1;
+      if (!_next_state()) break;
+
+    } else if (regs[vfd.reg].type == vfd.state && _exec_command()) break;
+  }
+}
+
+
+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) {
+  // Handle error
+  if (!ok) {
+    if (vfd.shutdown) _disconnected();
+    else _connect();
+    return;
+  }
+
+  // Handle read result
+  switch (regs[vfd.reg].type) {
+  case REG_MAX_FREQ_READ: vfd.max_freq = value; break;
+  case REG_FREQ_READ: vfd.actual_speed = value / (float)vfd.max_freq; break;
+
+  case REG_FREQ_SIGN_READ:
+    vfd.actual_speed = (int16_t)value / (float)vfd.max_freq;
+    break;
+
+  default: break;
+  }
+
+  // Next
+  _next_reg();
+}
+
+
+static bool _exec_command() {
+  if (vfd.wait) return true;
+
+  vfd_reg_t reg = regs[vfd.reg];
+  bool read = false;
+  bool write = false;
+
+  switch (reg.type) {
+  case REG_DISABLED: break;
+
+  case REG_MAX_FREQ_FIXED: vfd.max_freq = reg.value; break;
+
+  case REG_FREQ_SET:
+    write = true;
+    reg.value = fabs(vfd.speed) * vfd.max_freq;
+    break;
+
+  case REG_FREQ_SIGN_SET:
+    write = true;
+    reg.value = vfd.speed * vfd.max_freq;
+    break;
+
+  case REG_CONNECT_WRITE:
+  case REG_STOP_WRITE:
+  case REG_FWD_WRITE:
+  case REG_REV_WRITE:
+  case REG_DISCONNECT_WRITE:
+    write = true;
+    break;
+
+  case REG_FREQ_READ:
+  case REG_FREQ_SIGN_READ:
+  case REG_MAX_FREQ_READ:
+    read = true;
+    break;
+  }
+
+  if (read) modbus_read(reg.addr, _modbus_cb);
+  else if (write) modbus_write(reg.addr, reg.value, _modbus_cb);
+  else return false;
+
+  return true;
+}
+
+
+static void _load(const vfd_reg_t *_regs) {
+  memset(&regs, 0, sizeof(regs));
+
+  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;
+    regs[i].addr = pgm_read_word(&_regs[i].addr);
+    regs[i].value = pgm_read_word(&_regs[i].value);
+  }
+}
+
+
+void vfd_spindle_init() {
+  memset(&vfd, 0, sizeof(vfd));
+  modbus_init();
+
+  switch (spindle_get_type()) {
+  case SPINDLE_TYPE_CUSTOM:  memcpy(regs, custom_regs, sizeof(regs)); break;
+  case SPINDLE_TYPE_YL600:   _load(yl600_regs);   break;
+  case SPINDLE_TYPE_AC_TECH: _load(ac_tech_regs); break;
+  default: break;
+  }
+
+  _connect();
+}
+
+
+void vfd_spindle_deinit(deinit_cb_t cb) {
+  vfd.shutdown = true;
+  vfd.deinit_cb = cb;
+}
+
+
+void vfd_spindle_set(float speed) {
+  if (vfd.speed != speed) {
+    vfd.speed = speed;
+    vfd.changed = true;
+  }
+}
+
+
+float vfd_spindle_get() {return vfd.actual_speed;}
+void vfd_spindle_stop() {vfd_spindle_set(0);}
+
+
+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;}
+uint8_t get_vfd_reg_type(int reg) {return regs[reg].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) {
+  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) {
+  custom_regs[reg].value = value;
+  if (spindle_get_type() == SPINDLE_TYPE_CUSTOM)
+    regs[reg].value = custom_regs[reg].value;
+  vfd.changed = true;
+}
diff --git a/src/avr/src/vfd_spindle.h b/src/avr/src/vfd_spindle.h
new file mode 100644 (file)
index 0000000..db7375f
--- /dev/null
@@ -0,0 +1,38 @@
+/******************************************************************************\
+
+                 This file is part of the Buildbotics firmware.
+
+                   Copyright (c) 2015 - 2018, Buildbotics LLC
+                              All rights reserved.
+
+      This file ("the software") is free software: you can redistribute it
+      and/or modify it under the terms of the GNU General Public License,
+       version 2 as published by the Free Software Foundation. You should
+       have received a copy of the GNU General Public License, version 2
+      along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+      The software is distributed in the hope that it will be useful, but
+           WITHOUT ANY WARRANTY; without even the implied warranty of
+       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+                Lesser General Public License for more details.
+
+        You should have received a copy of the GNU Lesser General Public
+                 License along with the software.  If not, see
+                        <http://www.gnu.org/licenses/>.
+
+                 For information regarding this software email:
+                   "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#pragma once
+
+#include "spindle.h"
+
+
+void vfd_spindle_init();
+void vfd_spindle_deinit(deinit_cb_t cb);
+void vfd_spindle_set(float speed);
+float vfd_spindle_get();
+void vfd_spindle_stop();
+void vfd_spindle_rtc_callback();
diff --git a/src/avr/src/vfd_test.c b/src/avr/src/vfd_test.c
new file mode 100644 (file)
index 0000000..318d302
--- /dev/null
@@ -0,0 +1,144 @@
+/******************************************************************************\
+
+                 This file is part of the Buildbotics firmware.
+
+                   Copyright (c) 2015 - 2018, Buildbotics LLC
+                              All rights reserved.
+
+      This file ("the software") is free software: you can redistribute it
+      and/or modify it under the terms of the GNU General Public License,
+       version 2 as published by the Free Software Foundation. You should
+       have received a copy of the GNU General Public License, version 2
+      along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+      The software is distributed in the hope that it will be useful, but
+           WITHOUT ANY WARRANTY; without even the implied warranty of
+       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+                Lesser General Public License for more details.
+
+        You should have received a copy of the GNU Lesser General Public
+                 License along with the software.  If not, see
+                        <http://www.gnu.org/licenses/>.
+
+                 For information regarding this software email:
+                   "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#include "vfd_test.h"
+#include "modbus.h"
+#include "status.h"
+#include "command.h"
+#include "type.h"
+#include "exec.h"
+
+#include <string.h>
+
+
+static struct {
+  bool enabled;
+  bool waiting;
+  uint16_t read_response;
+  deinit_cb_t deinit_cb;
+} vt;
+
+
+static void _shutdown() {
+  if (vt.waiting || vt.enabled) return;
+  modbus_deinit();
+  if (vt.deinit_cb) vt.deinit_cb();
+}
+
+
+void vfd_test_init() {
+  modbus_init();
+  vt.enabled = true;
+  vt.waiting = false;
+}
+
+
+void vfd_test_deinit(deinit_cb_t cb) {
+  vt.enabled = false;
+  vt.deinit_cb = cb;
+  _shutdown();
+}
+
+
+void vfd_test_set(float speed) {}
+float vfd_test_get() {return 0;}
+void vfd_test_stop() {}
+
+
+// Variable callbacks
+uint16_t get_modbus_response() {return vt.read_response;}
+
+
+// Command callbacks
+static stat_t _modbus_cmd_exec() {
+  if (vt.waiting) return STAT_NOP;
+  exec_set_cb(0);
+  return STAT_AGAIN;
+}
+
+
+static void _modbus_rw_cb(bool ok, uint16_t addr, uint16_t value) {
+  vt.read_response = value; // Always zero on error
+  vt.waiting = false;
+  _shutdown();
+}
+
+
+stat_t command_modbus_read(char *cmd) {
+  stat_t status = STAT_OK;
+  uint16_t addr = type_parse_u16(cmd + 1, &status);
+  if (status == STAT_OK) command_push(*cmd, &addr);
+
+  return status;
+}
+
+
+unsigned command_modbus_read_size() {return sizeof(uint16_t);}
+
+
+void command_modbus_read_exec(void *data) {
+  if (!vt.enabled) return;
+
+  uint16_t addr = *(uint16_t *)data;
+
+  vt.waiting = true;
+  modbus_read(addr, _modbus_rw_cb);
+  exec_set_cb(_modbus_cmd_exec);
+}
+
+
+
+stat_t command_modbus_write(char *cmd) {
+  // Get value
+  char *value = strchr(cmd + 1, '=');
+  if (!value) return STAT_INVALID_COMMAND;
+  *value++ = 0;
+
+  stat_t status = STAT_OK;
+  uint16_t buffer[2];
+  buffer[0] = type_parse_u16(cmd + 1, &status);
+  if (status == STAT_OK) buffer[1] = type_parse_u16(value, &status);
+
+  if (status == STAT_OK) command_push(*cmd, buffer);
+
+  return status;
+}
+
+
+unsigned command_modbus_write_size() {return 2 * sizeof(uint16_t);}
+
+
+void command_modbus_write_exec(void *data) {
+  if (!vt.enabled) return;
+
+  uint16_t addr = ((uint16_t *)data)[0];
+  uint16_t value = ((uint16_t *)data)[1];
+
+  vt.waiting = true;
+  modbus_write(addr, value, _modbus_rw_cb);
+  exec_set_cb(_modbus_cmd_exec);
+}
diff --git a/src/avr/src/vfd_test.h b/src/avr/src/vfd_test.h
new file mode 100644 (file)
index 0000000..c0ac19d
--- /dev/null
@@ -0,0 +1,37 @@
+/******************************************************************************\
+
+                 This file is part of the Buildbotics firmware.
+
+                   Copyright (c) 2015 - 2018, Buildbotics LLC
+                              All rights reserved.
+
+      This file ("the software") is free software: you can redistribute it
+      and/or modify it under the terms of the GNU General Public License,
+       version 2 as published by the Free Software Foundation. You should
+       have received a copy of the GNU General Public License, version 2
+      along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+      The software is distributed in the hope that it will be useful, but
+           WITHOUT ANY WARRANTY; without even the implied warranty of
+       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+                Lesser General Public License for more details.
+
+        You should have received a copy of the GNU Lesser General Public
+                 License along with the software.  If not, see
+                        <http://www.gnu.org/licenses/>.
+
+                 For information regarding this software email:
+                   "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#pragma once
+
+#include "spindle.h"
+
+
+void vfd_test_init();
+void vfd_test_deinit(deinit_cb_t cb);
+void vfd_test_set(float speed);
+float vfd_test_get();
+void vfd_test_stop();
index 487aba422ad16c9358f8075cefd17fcd987ade6b..41f422f149995e6af0559f5a501e8cca5f55cd74 100644 (file)
@@ -376,7 +376,8 @@ script#cheat-sheet-view-template(type="text/x-template")
         th(colspan='3') Flow-control Codes
       tr
         td
-          a(target="_blank", href="#{base}/o-code.html#ocode:subroutines") o sub
+          a(target="_blank", href="#{base}/o-code.html#ocode:subroutines")
+            | o sub/endsub/call
         td
         td Subroutines, sub/endsub call
       tr
@@ -404,27 +405,27 @@ script#cheat-sheet-view-template(type="text/x-template")
           a(target="_blank", href="#{base}/o-code.html#ocode:calling-files")
             | o call
         td
-        td Call named file
+        td Call named or numbered file
 
-      tr.spacer-row.unimplemented(v-if="showUnimplemented"): th
-      tr.header-row.unimplemented(v-if="showUnimplemented")
+      tr.spacer-row: th
+      tr.header-row
         th(colspan='3') Modal State
-      tr.unimplemented(v-if="showUnimplemented")
+      tr
         td
           a(target="_blank", href="#{base}/m-code.html#mcode:m70") M70
         td
         td Save modal state
-      tr.unimplemented(v-if="showUnimplemented")
+      tr
         td
           a(target="_blank", href="#{base}/m-code.html#mcode:m71") M71
         td
         td Invalidate stored state
-      tr.unimplemented(v-if="showUnimplemented")
+      tr
         td
           a(target="_blank", href="#{base}/m-code.html#mcode:m72") M72
         td
         td Restore modal state
-      tr.unimplemented(v-if="showUnimplemented")
+      tr
         td
           a(target="_blank", href="#{base}/m-code.html#mcode:m73") M73
         td
index edea72b1830e928aaf9f963f89479039f70e86d0..730922dbc74d96550532a4c01416dd7c833ffe80 100644 (file)
@@ -32,4 +32,4 @@ script#gcode-view-template(type="text/x-template")
     form.pure-form.pure-form-aligned
       fieldset
         templated-input(v-for="templ in template.gcode", :name="$key",
-          :model.sync="gcode[$key]", :template="templ")
+          :model.sync="config.gcode[$key]", :template="templ")
index 17a4c900a7b18af30b599a9637b3a0ea1b7321de..511a4ffac8bd76e8b1ba47544d6accb5ccf8f866 100644 (file)
@@ -172,7 +172,7 @@ script#indicators-template(type="text/x-template")
         th.header(colspan=5) RS485 Spindle
 
       tr
-        th(colspan=5) {{state['he'] ? "" : "Not "}}Connected
+        th(colspan=5) {{modbus_status}}
 
       tr
         td {{state['hz']}} Hz
index e433fe3c5cf969c0074ae810cf07c9e61606933d..980a973bd1168a6bcee774797dab02da4fd37d33 100644 (file)
@@ -33,10 +33,10 @@ script#io-view-template(type="text/x-template")
     form.pure-form.pure-form-aligned
       fieldset
         templated-input(v-for="templ in template.switches", :name="$key",
-          :model.sync="switches[$key]", :template="templ")
+          :model.sync="config.switches[$key]", :template="templ")
 
     h2 Outputs
     form.pure-form.pure-form-aligned
       fieldset
         templated-input(v-for="templ in template.outputs", :name="$key",
-          :model.sync="outputs[$key]", :template="templ")
+          :model.sync="config.outputs[$key]", :template="templ")
diff --git a/src/jade/templates/modbus-reg-view.jade b/src/jade/templates/modbus-reg-view.jade
new file mode 100644 (file)
index 0000000..ac86cfd
--- /dev/null
@@ -0,0 +1,45 @@
+//-/////////////////////////////////////////////////////////////////////////////
+//-                                                                           //
+//-              This file is part of the Buildbotics firmware.               //
+//-                                                                           //
+//-                Copyright (c) 2015 - 2018, Buildbotics LLC                 //
+//-                           All rights reserved.                            //
+//-                                                                           //
+//-   This file ("the software") is free software: you can redistribute it    //
+//-   and/or modify it under the terms of the GNU General Public License,     //
+//-    version 2 as published by the Free Software Foundation. You should     //
+//-    have received a copy of the GNU General Public License, version 2      //
+//-   along with the software. If not, see <http://www.gnu.org/licenses/>.    //
+//-                                                                           //
+//-   The software is distributed in the hope that it will be useful, but     //
+//-        WITHOUT ANY WARRANTY; without even the implied warranty of         //
+//-    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU      //
+//-             Lesser General Public License for more details.               //
+//-                                                                           //
+//-     You should have received a copy of the GNU Lesser General Public      //
+//-              License along with the software.  If not, see                //
+//-                     <http://www.gnu.org/licenses/>.                       //
+//-                                                                           //
+//-              For information regarding this software email:               //
+//-                "Joseph Coffland" <joseph@buildbotics.com>                 //
+//-                                                                           //
+//-/////////////////////////////////////////////////////////////////////////////
+
+script#modbus-reg-view-template(type="text/x-template")
+  tr.modbus-reg
+    td.reg-index {{index}}
+    td.reg-type
+      select(v-model="model['reg-type']", @change="change")
+        option(v-for="opt in template['reg-type']['values']", :value="opt")
+          | {{opt}}
+
+    td.reg-addr
+      input(v-model="model['reg-addr']", @change="change", type="text",
+        :min="template['reg-addr'].min", :max="template['reg-addr'].max",
+        pattern="[0-9]*", :disabled="model['reg-type'] == 'disabled'",
+        number)
+
+    td.reg-value
+      input(v-model="model['reg-value']", @change="change", type="text",
+        :min="template['reg-value'].min", :max="template['reg-value'].max",
+        pattern="[0-9]*", :disabled="!has_user_value", number)
index 4b083fe3029d7b37c69834edba93212403b5e0c3..09b72528c4eb171ab4f831bb10c295de4f8d4116 100644 (file)
 //-/////////////////////////////////////////////////////////////////////////////
 
 script#motor-view-template(type="text/x-template")
-  #motor
+  .motor(:class="{slave: is_slave}")
     h1 Motor {{index}} Configuration
 
     form.pure-form.pure-form-aligned
-      fieldset(v-for="category in template.motors", :class="$key")
+      fieldset(v-for="category in template.motors.template", :class="$key")
         h2 {{$key}}
 
         templated-input(v-for="templ in category", :name="$key",
           :model.sync="motor[$key]", :template="templ")
 
           label.extra(v-if="$key == 'max-velocity'", slot="extra",
-            title="Revolutions Per Minute")
-            | ({{1000 * motor[$key] / motor['travel-per-rev'] | fixed 0}} RPM)
+            title="Revolutions Per Minute") ({{rpm | fixed 0}} RPM)
 
           label.extra(v-if="$key == 'max-accel'", slot="extra",
-            title="G-force")
-            | ({{motor[$key] * 0.0283254504 | fixed 3}} g)
+            title="G-force") ({{gForce | fixed 3}} g)
 
           label.extra(v-if="$key == 'max-jerk'", slot="extra",
-            title="G-force per minute")
-            | ({{motor[$key] * 0.0283254504 | fixed 2}} g/min)
+            title="G-force per minute") ({{gForcePerMin | fixed 2}} g/min)
 
           label.extra(v-if="$key == 'step-angle'", slot="extra",
-            title="Steps per revolution")
-            | ({{360 / motor[$key] | fixed 0}} steps/rev)
+            title="Steps per revolution") ({{stepsPerRev | fixed 0}} steps/rev)
 
           label.extra(v-if="$key == 'travel-per-rev'", slot="extra",
-            title="Micrometers per step")
-            | ({{motor[$key] * motor['step-angle'] / 0.36 | fixed 1}}
-            | &nbsp;µm/step)
+            title="Micrometers per step") ({{umPerStep | fixed 1}} µm/step)
index 5ab1f72c50a9edc854360414a3f71b256111278b..a264f4289c92d8f8e3b22dfb94baa7a75dc1b2a1 100644 (file)
@@ -31,28 +31,28 @@ script#templated-input-template(type="text/x-template")
     label(:for="name") {{name}}
 
     select(v-if="template.type == 'enum' || template.values", v-model="model",
-      :id="name", @change="change")
+      :name="name", @change="change")
       option(v-for="opt in template.values", :value="opt") {{opt}}
 
     input(v-if="template.type == 'bool'", type="checkbox",
-      v-model="model", :id="name", @change="change")
+      v-model="model", :name="name", @change="change")
 
     input(v-if="template.type == 'float'", v-model="model", number,
       :min="template.min", :max="template.max", :step="template.step || 'any'",
-        type="number", :id="name", @change="change")
+        type="number", :name="name", @change="change")
 
     input(v-if="template.type == 'int' && !template.values", v-model="model",
       number, :min="template.min", :max="template.max", type="number",
-      :id="name", @change="change")
+      :name="name", @change="change")
 
     input(v-if="template.type == 'string'", v-model="model",
-      type="text", :id="name", @change="change")
+      type="text", :name="name", @change="change")
 
     textarea(v-if="template.type == 'text'", v-model="model",
-      :id="name", @change="change")
+      :name="name", @change="change")
 
     span.range(v-if="template.type == 'percent'")
-      input(type="range", v-model="model", :id="name", number, min="0",
+      input(type="range", v-model="model", :name="name", number, min="0",
         max="100", step="1", @change="change")
       | {{model}}
 
index 8be586fa3621013f34ef72a8cd304c9e38acfb55..6f33f1b3788c1b8f60c16308ff8b845681e35d81 100644 (file)
@@ -32,19 +32,74 @@ script#tool-view-template(type="text/x-template")
     form.pure-form.pure-form-aligned
       fieldset
         templated-input(v-for="templ in template.tool", :name="$key",
-          :model.sync="tool[$key]", :template="templ")
+          :model.sync="config.tool[$key]", :template="templ",
+          v-if="tool_type != 'DISABLED' || $key == 'tool-type'")
 
-    div(v-if="get_type() == 'PWM'")
+    div(v-if="tool_type == 'PWM SPINDLE'")
       h2 PWM Spindle
       form.pure-form.pure-form-aligned
         fieldset
           templated-input(v-for="templ in template['pwm-spindle']",
-            :name="$key", :model.sync="pwmSpindle[$key]", :template="templ")
+            :name="$key", :model.sync="config['pwm-spindle'][$key]",
+            :template="templ")
 
-    div(v-if="get_type() != 'DISABLED' && get_type() != 'PWM'")
+    div(v-if="is_modbus")
       h2 Modbus Configuration
       form.pure-form.pure-form-aligned
         fieldset
           templated-input(v-for="templ in template['modbus-spindle']",
-            :name="$key", :model.sync="modbusSpindle[$key]",
-            :template="templ")
+            :name="$key", :model.sync="config['modbus-spindle'][$key]",
+            :template="templ", v-if="$key != 'regs'")
+
+    div(v-if="tool_type == 'VFD TEST'")
+      h2 Modbus Test
+      form.pure-form
+        table.modbus-regs
+          tr
+            th Address
+            th Value
+            th Action
+            th Status
+          tr
+            td: input(name="address", type="text", v-model="address", number)
+            td: input(name="value", type="text", v-model="value", number)
+            td
+              button.pure-button(@click="read") Read
+              button.pure-button(@click="write") Write
+            td.modbus-status {{modbus_status}}
+
+    div.modbus-program(v-if="is_modbus && this.tool_type != 'HUANYANG VFD'")
+      h2 Active Modbus Program
+      form.pure-form
+        table.modbus-regs.fixed-regs
+          tr
+            th Index
+            th Command
+            th Address
+            th Value
+
+          tr(v-for="(index, reg) in regs_tmpl.index", v-if="state[reg + 'vt']")
+            td.reg-index {{index}}
+            td.reg-type {{get_reg_type(reg)}}
+            td.reg-addr {{get_reg_addr(reg)}}
+            td.reg-value {{get_reg_value(reg)}}
+
+      button.pure-button-secondary(@click="customize") Customize
+      button.pure-button-secondary(@click="clear") Clear
+
+    div(v-if="tool_type == 'CUSTOM MODBUS VFD'")
+      h2 Edit Modbus Program
+      form.pure-form
+        table.modbus-regs
+          tr
+            th Index
+            th Command
+            th Address
+            th Value
+
+          tr(v-for="(index, reg) in config['modbus-spindle'].regs",
+            is="modbus-reg", :index="index", :model.sync="reg",
+            :template="template['modbus-spindle'].regs.template",
+            v-if="!index || reg['reg-type'] != 'disabled' || " +
+            "config['modbus-spindle'].regs[index - 1]['reg-type'] != " +
+            "'disabled'")
index 78fecc5309d36793f5243ea1824fbc02e5f333be..a66b99fdc141f4baeb2df32d59ea3d11ddfb80c4 100644 (file)
@@ -85,8 +85,8 @@ module.exports = new Vue({
       currentView: 'loading',
       index: -1,
       modified: false,
-      template: {motors: {}, axes: {}},
-      config: {motors: [{}, {}, {}, {}], admin: {}, version: '<loading>'},
+      template: {motors: {template: {}}},
+      config: {motors: [{}, {}, {}, {}], version: '<loading>'},
       state: {},
       messages: [],
       errorTimeout: 30,
index d3d07a7255591803389d40bed542dae4ee7f597b..a8c10a14ce0728338d33415fa5d02bbcc9200dff 100644 (file)
@@ -160,13 +160,7 @@ module.exports = {
 
     get_axis_motor_param: function (axis, name) {
       var motor = this.get_axis_motor(axis);
-      if (typeof motor == 'undefined') return;
-      if (typeof motor[name] != 'undefined') return motor[name];
-
-      for (var section in this.template.motors) {
-        var sec = this.template.motors[section];
-        if (typeof sec[name] != 'undefined') return sec[name]['default'];
-      }
+      if (typeof motor != 'undefined') return motor[name];
     },
 
 
diff --git a/src/js/gauge.js b/src/js/gauge.js
deleted file mode 100644 (file)
index b08b5ae..0000000
+++ /dev/null
@@ -1,94 +0,0 @@
-/******************************************************************************\
-
-                 This file is part of the Buildbotics firmware.
-
-                   Copyright (c) 2015 - 2018, Buildbotics LLC
-                              All rights reserved.
-
-      This file ("the software") is free software: you can redistribute it
-      and/or modify it under the terms of the GNU General Public License,
-       version 2 as published by the Free Software Foundation. You should
-       have received a copy of the GNU General Public License, version 2
-      along with the software. If not, see <http://www.gnu.org/licenses/>.
-
-      The software is distributed in the hope that it will be useful, but
-           WITHOUT ANY WARRANTY; without even the implied warranty of
-       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
-                Lesser General Public License for more details.
-
-        You should have received a copy of the GNU Lesser General Public
-                 License along with the software.  If not, see
-                        <http://www.gnu.org/licenses/>.
-
-                 For information regarding this software email:
-                   "Joseph Coffland" <joseph@buildbotics.com>
-
-\******************************************************************************/
-
-'use strict';
-
-
-module.exports = Vue.extend({
-  template: '<div class="gauge"><canvas></canvas><span></span></div>',
-
-
-  props: {
-    value: {tupe: Number, required: true},
-    lines: {type: Number, default: 1},
-    angle: {type: Number, default: 0.1},
-    lineWidth: {type: Number, default: 0.25},
-    ptrLength: {type: Number, default: 0.85},
-    ptrStrokeWidth: {type: Number, default: 0.054},
-    ptrColor: {type: String, default: '#666'},
-    limitMax: {type: Boolean, default: true},
-    colorStart: {type: String, default: '#6FADCF'},
-    colorStop: {type: String, default: '#8FC0DA'},
-    strokeColor: String,
-    min: {type: Number, default: 0},
-    max: {type: Number, default: 100}
-  },
-
-
-  data: function () {
-    return {
-    }
-  },
-
-
-  watch: {
-    value: function (value) {this.set(value)}
-  },
-
-
-  compiled: function () {
-    this.gauge = new Gauge(this.$el.children[0]).setOptions({
-      lines: this.lines,
-      angle: this.angle,
-      lineWidth: this.lineWidth,
-      pointer: {
-        length: this.ptrLength,
-        strokeWidth: this.ptrStrokeWidth,
-        color: this.ptrColor
-      },
-      limitMax: this.limitMax,
-      colorStart: this.colorStart,
-      colorStop: this.colorStop,
-      strokeColor: this.strokeColor,
-      minValue: this.min,
-      maxValue: this.max
-   });
-
-    this.gauge.minValue = parseInt(this.min);
-    this.gauge.maxValue = parseInt(this.max);
-    this.set(this.value);
-
-    this.gauge.setTextField(this.$el.children[1]);
-  },
-
-
-  methods: {
-    set: function (value) {
-      if (typeof value == 'number') this.gauge.set(value);
-    }
-  }
-})
index cdafcd7e5dfc7d41835dc2592635e7be643390ea..9042c07f00af57106dec32aa3c731b33e5abd5c7 100644 (file)
@@ -33,35 +33,10 @@ module.exports = {
   props: ['config', 'template'],
 
 
-  data: function () {
-    return {
-      gcode: {}
-    }
-  },
-
-
   events: {
     'input-changed': function() {
       this.$dispatch('config-changed');
       return false;
     }
-  },
-
-
-  ready: function () {this.update()},
-
-
-  methods: {
-    update: function () {
-      Vue.nextTick(function () {
-        if (this.config.hasOwnProperty('gcode'))
-          this.gcode = this.config.gcode;
-
-        var template = this.template.gcode;
-        for (var key in template)
-          if (!this.gcode.hasOwnProperty(key))
-            this.$set('gcode["' + key + '"]', template[key].default);
-      }.bind(this));
-    }
   }
 }
index 25f8f35d4f74fc1563ba4ebf805288c2091969da..7b98eb53f1f3ff564d340ab7a8b5d2794873f91b 100644 (file)
 
 'use strict'
 
+var modbus = require('./modbus.js');
+
 
 module.exports = {
   template: '#indicators-template',
   props: ['state'],
 
 
+  computed: {
+    modbus_status: function () {return modbus.status_to_string(this.state.mx)}
+  },
+
+
   methods: {
     is_motor_enabled: function (motor) {
       return typeof this.state[motor + 'pm'] != 'undefined' &&
index f4f3465c7ce47a7cc463bc537e8316e4aef59270..c42b78a4b71b8b33850d3c045f1e94f0015f9e45 100644 (file)
@@ -33,48 +33,10 @@ module.exports = {
   props: ['config', 'template'],
 
 
-  data: function () {
-    return {
-      switches: {},
-      outputs: {}
-    }
-  },
-
-
   events: {
     'input-changed': function() {
       this.$dispatch('config-changed');
       return false;
     }
-  },
-
-
-  ready: function () {this.update()},
-
-
-  methods: {
-    update: function () {
-      Vue.nextTick(function () {
-        // Switches
-        if (this.config.hasOwnProperty('switches'))
-          this.switches = this.config.switches;
-        else this.switches = {};
-
-        var template = this.template.switches;
-        for (var key in template)
-          if (!this.switches.hasOwnProperty(key))
-            this.$set('switches["' + key + '"]', template[key].default);
-
-        // Outputs
-        if (this.config.hasOwnProperty('outputs'))
-          this.outputs = this.config.outputs;
-        else this.outputs = {};
-
-        template = this.template.outputs;
-        for (key in template)
-          if (!this.outputs.hasOwnProperty(key))
-            this.$set('outputs["' + key + '"]', template[key].default);
-      }.bind(this));
-    }
   }
 }
diff --git a/src/js/modbus-reg.js b/src/js/modbus-reg.js
new file mode 100644 (file)
index 0000000..224f22e
--- /dev/null
@@ -0,0 +1,48 @@
+/******************************************************************************\
+
+                 This file is part of the Buildbotics firmware.
+
+                   Copyright (c) 2015 - 2018, Buildbotics LLC
+                              All rights reserved.
+
+      This file ("the software") is free software: you can redistribute it
+      and/or modify it under the terms of the GNU General Public License,
+       version 2 as published by the Free Software Foundation. You should
+       have received a copy of the GNU General Public License, version 2
+      along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+      The software is distributed in the hope that it will be useful, but
+           WITHOUT ANY WARRANTY; without even the implied warranty of
+       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+                Lesser General Public License for more details.
+
+        You should have received a copy of the GNU Lesser General Public
+                 License along with the software.  If not, see
+                        <http://www.gnu.org/licenses/>.
+
+                 For information regarding this software email:
+                   "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+'use strict'
+
+
+module.exports = {
+  replace: true,
+  template: '#modbus-reg-view-template',
+  props: ['index', 'model', 'template', 'enable'],
+
+
+  computed: {
+    has_user_value: function () {
+      var type = this.model['reg-type'];
+      return type.indexOf('write') != -1 || type.indexOf('fixed') != -1;
+    }
+  },
+
+
+  methods: {
+    change: function () {this.$dispatch('input-changed')}
+  }
+}
diff --git a/src/js/modbus.js b/src/js/modbus.js
new file mode 100644 (file)
index 0000000..83a7504
--- /dev/null
@@ -0,0 +1,51 @@
+/******************************************************************************\
+
+                 This file is part of the Buildbotics firmware.
+
+                   Copyright (c) 2015 - 2018, Buildbotics LLC
+                              All rights reserved.
+
+      This file ("the software") is free software: you can redistribute it
+      and/or modify it under the terms of the GNU General Public License,
+       version 2 as published by the Free Software Foundation. You should
+       have received a copy of the GNU General Public License, version 2
+      along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+      The software is distributed in the hope that it will be useful, but
+           WITHOUT ANY WARRANTY; without even the implied warranty of
+       MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
+                Lesser General Public License for more details.
+
+        You should have received a copy of the GNU Lesser General Public
+                 License along with the software.  If not, see
+                        <http://www.gnu.org/licenses/>.
+
+                 For information regarding this software email:
+                   "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+'use strict'
+
+
+// Must match modbus.c
+var exports = {
+  DISCONNECTED: 0,
+  OK:           1,
+  CRC:          2,
+  INVALID:      3,
+  TIMEDOUT:     4
+};
+
+
+exports.status_to_string =
+  function (status) {
+    if (status == exports.OK)       return 'Ok';
+    if (status == exports.CRC)      return 'CRC error';
+    if (status == exports.INVALID)  return 'Invalid response';
+    if (status == exports.TIMEDOUT) return 'Timedout';
+    return 'Disconnected';
+  }
+
+
+module.exports = exports;
index 08a4763e17d9623b844bd09db9591c6f5f8c4b65..51627aae0239a19d39d44908e6c57d820c45ae17 100644 (file)
@@ -33,72 +33,39 @@ module.exports = {
   props: ['index', 'config', 'template'],
 
 
-  data: function () {
-    return {
-      active: false,
-      motor: {}
-    }
-  },
-
-
-  watch: {
-    index: function() {this.update()}
-  },
-
+  computed: {
+    is_slave: function () {
+      for (var i = 0; i < this.index; i++)
+        if (this.motor.axis == this.config.motors[i].axis)
+          return true;
 
-  events: {
-    'input-changed': function() {
-      this.slave_update();
-      this.$dispatch('config-changed');
       return false;
-    }
-  },
-
+    },
 
-  attached: function () {this.active = true; this.update()},
-  detached: function () {this.active = false},
 
+    motor: function () {return this.config.motors[this.index]},
 
-  methods: {
-    slave_update: function () {
-      var slave = false;
-      for (var i = 0; i < this.index; i++)
-        if (this.motor.axis == this.config.motors[i].axis)
-          slave = true;
 
-      var el = $(this.$el);
-
-      if (slave) {
-        el.find('.axis .units').text('(slave motor)');
-        el.find('.limits, .homing, .motion').find('input, select')
-          .attr('disabled', 1);
-        el.find('.power-mode select').attr('disabled', 1);
-        el.find('.motion .reverse input').removeAttr('disabled');
-
-      } else {
-        el.find('.axis .units').text('');
-        el.find('input,select').removeAttr('disabled');
-      }
+    rpm: function () {
+      return 1000 * this.motor['max-velocity'] / this.motor['travel-per-rev'];
     },
 
 
-    update: function () {
-      if (!this.active) return;
+    gForce: function () {return this.motor['max-accel'] * 0.0283254504},
+    gForcePerMin: function () {return this.motor['max-jerk'] * 0.0283254504},
+    stepsPerRev: function () {return 360 / this.motor['step-angle']},
 
-      Vue.nextTick(function () {
-        if (this.config.hasOwnProperty('motors'))
-          this.motor = this.config.motors[this.index];
-        else this.motor = {};
 
-        var template = this.template.motors;
-        for (var category in template)
-          for (var key in template[category])
-            if (!this.motor.hasOwnProperty(key))
-              this.$set('motor["' + key + '"]',
-                        template[category][key].default);
+    umPerStep: function () {
+      return this.motor['travel-per-rev'] * this.motor['step-angle'] / 0.36
+    }
+  },
+
 
-        this.slave_update();
-      }.bind(this));
+  events: {
+    'input-changed': function() {
+      this.$dispatch('config-changed');
+      return false;
     }
   }
 }
index 498fe3cac563a1ef6b864d008113572bf460da04..0483d4ce5ed183d8f716816956bda6205319ed13 100644 (file)
 
 'use strict';
 
+var api = require('./api');
+var modbus = require('./modbus.js');
+
 
 module.exports = {
   template: '#tool-view-template',
-  props: ['config', 'template'],
+  props: ['config', 'template', 'state'],
 
 
   data: function () {
     return {
-      tool: {},
-      pwmSpindle: {},
-      modbusSpindle: {}
+      address: 0,
+      value: 0
     }
   },
 
 
+  components: {'modbus-reg': require('./modbus-reg.js')},
+
+
+  watch: {
+    'state.mr': function () {this.value = this.state.mr}
+  },
+
+
   events: {
     'input-changed': function() {
       this.$dispatch('config-changed');
@@ -50,39 +60,73 @@ module.exports = {
   },
 
 
-  ready: function () {this.update()},
+  ready: function () {this.value = this.state.mr},
+
+
+  computed: {
+    regs_tmpl: function () {return this.template['modbus-spindle'].regs},
+    tool_type: function () {return this.config.tool['tool-type'].toUpperCase()},
+
+
+    is_modbus: function () {
+      return this.tool_type != 'DISABLED' && this.tool_type != 'PWM SPINDLE'
+    },
+
+
+    modbus_status: function () {return modbus.status_to_string(this.state.mx)}
+  },
 
 
   methods: {
-    get_type: function () {
-      return (this.tool['spindle-type'] || 'Disabled').toUpperCase();
+    get_reg_type: function (reg) {
+      return this.regs_tmpl.template['reg-type'].values[this.state[reg + 'vt']]
+    },
+
+
+    get_reg_addr: function (reg) {return this.state[reg + 'va']},
+    get_reg_value: function (reg) {return this.state[reg + 'vv']},
+
+
+    read: function (e) {
+      e.preventDefault();
+      api.put('modbus/read', {address: this.address});
     },
 
 
-    update_tool: function (type) {
-      if (this.config.hasOwnProperty(type + '-spindle'))
-        this[type + 'Spindle'] = this.config[type + '-spindle'];
+    write: function (e) {
+      e.preventDefault();
+      api.put('modbus/write', {address: this.address, value: this.value});
+    },
+
+
+    customize: function (e) {
+      e.preventDefault();
+      this.config.tool['tool-type'] = 'Custom Modbus VFD';
 
-      var template = this.template[type + '-spindle'];
-      for (var key in template)
-        if (!this[type + 'Spindle'].hasOwnProperty(key))
-          this.$set(type + 'Spindle["' + key + '"]', template[key].default);
+      var regs = this.config['modbus-spindle'].regs;
+      for (var i = 0; i < regs.length; i++) {
+        var reg = this.regs_tmpl.index[i];
+        regs[i]['reg-type']  = this.get_reg_type(reg);
+        regs[i]['reg-addr']  = this.get_reg_addr(reg);
+        regs[i]['reg-value'] = this.get_reg_value(reg);
+      }
+
+      this.$dispatch('config-changed');
     },
 
 
-    update: function () {
-      Vue.nextTick(function () {
-        if (this.config.hasOwnProperty('tool'))
-          this.tool = this.config.tool;
+    clear: function (e) {
+      e.preventDefault();
+      this.config.tool['tool-type'] = 'Custom Modbus VFD';
 
-        var template = this.template.tool;
-        for (var key in template)
-          if (!this.tool.hasOwnProperty(key))
-            this.$set('tool["' + key + '"]', template[key].default);
+      var regs = this.config['modbus-spindle'].regs;
+      for (var i = 0; i < regs.length; i++) {
+        regs[i]['reg-type']  = 'disabled';
+        regs[i]['reg-addr']  = 0;
+        regs[i]['reg-value'] = 0;
+      }
 
-        this.update_tool('pwm');
-        this.update_tool('modbus');
-       }.bind(this));
+      this.$dispatch('config-changed');
     }
   }
 }
index 66d9cb8995216c4ca424605e9b596b759140013f..8bb3d9be57c272077a7193c771cae282fc069c17 100644 (file)
@@ -35,25 +35,27 @@ import logging
 log = logging.getLogger('Cmd')
 
 # Keep this in sync with AVR code command.def
-SET       = '$'
-SET_SYNC  = '#'
-SEEK      = 's'
-SET_AXIS  = 'a'
-LINE      = 'l'
-INPUT     = 'I'
-DWELL     = 'd'
-PAUSE     = 'P'
-STOP      = 'S'
-UNPAUSE   = 'U'
-JOG       = 'j'
-REPORT    = 'r'
-REBOOT    = 'R'
-RESUME    = 'c'
-ESTOP     = 'E'
-CLEAR     = 'C'
-FLUSH     = 'F'
-DUMP      = 'D'
-HELP      = 'h'
+SET          = '$'
+SET_SYNC     = '#'
+MODBUS_READ  = 'm'
+MODBUS_WRITE = 'M'
+SEEK         = 's'
+SET_AXIS     = 'a'
+LINE         = 'l'
+INPUT        = 'I'
+DWELL        = 'd'
+PAUSE        = 'P'
+STOP         = 'S'
+UNPAUSE      = 'U'
+JOG          = 'j'
+REPORT       = 'r'
+REBOOT       = 'R'
+RESUME       = 'c'
+ESTOP        = 'E'
+CLEAR        = 'C'
+FLUSH        = 'F'
+DUMP         = 'D'
+HELP         = 'h'
 
 SEEK_ACTIVE = 1 << 0
 SEEK_ERROR  = 1 << 1
@@ -79,7 +81,22 @@ def encode_axes(axes):
     return data
 
 
-def set(name, value): return '#%s=%s' % (name, value)
+def set_sync(name, value):
+    if isinstance(value, float): return set_float(name, value)
+    else: return SET_SYNC + '%s=%s' % (name, value)
+
+
+def set(name, value):
+    if isinstance(value, float): return set_float(name, value)
+    else: return SET + '%s=%s' % (name, value)
+
+
+def set_float(name, value):
+    return SET_SYNC + '%s=:%s' % (name, encode_float(value))
+
+
+def modbus_read(addr): return MODBUS_READ + '%d' % addr
+def modbus_write(addr, value): return MODBUS_WRITE + '%d=%d' % (addr, value)
 def set_axis(axis, position): return SET_AXIS + axis + encode_float(position)
 
 
index 42f0469184da29982083179f6e71e4a1f89596aa..03aa5041afe3c4ecb7ac85dfb1270475dfbe59fa 100644 (file)
@@ -69,14 +69,14 @@ class Comm(object):
         return len(self.queue) or self.command is not None
 
 
-    def i2c_command(self, cmd, byte = None, word = None):
-        log.info('I2C: ' + cmd)
+    def i2c_command(self, cmd, byte = None, word = None, block = None):
+        log.info('I2C: %s b=%s w=%s d=%s' % (cmd, byte, word, block))
         retry = 5
         cmd = ord(cmd[0])
 
         while True:
             try:
-                self.ctrl.i2c.write(self.i2c_addr, cmd, byte, word)
+                self.ctrl.i2c.write(self.i2c_addr, cmd, byte, word, block)
                 break
 
             except Exception as e:
index bb0e2a1b3221f349d08677e1c1d1edbca97844cd..b04ad63748d4d30d6a36b8a6fe10a586182e3980 100644 (file)
@@ -48,30 +48,19 @@ class CommandQueue():
         self.q.clear()
 
 
-    def _flush_cb(self, cb, *args, **kwargs):
-        self.clear()
-        cb(*args, **kwargs)
-
-
-    def flush(self, cb, *args, **kwargs):
-        id = self.lastEnqueueID + 1
-        self.enqueue(id, False, self._flush_cb, cb, args, kwargs)
-        return id
-
-
-    def enqueue(self, id, synchronized, cb, *args, **kwargs):
-        log.info('add(#%d, %s) releaseID=%d', id, synchronized, self.releaseID)
+    def enqueue(self, id, cb, *args, **kwargs):
+        log.info('add(#%d) releaseID=%d', id, self.releaseID)
         self.lastEnqueueID = id
-        self.q.append([id, synchronized, False, cb, args, kwargs])
+        self.q.append([id, cb, args, kwargs])
         self._release()
 
 
     def _release(self):
         while len(self.q):
-            id, synchronized, immediate, cb, args, kwargs = self.q[0]
+            id, cb, args, kwargs = self.q[0]
 
-            # Execute commands <= releaseID and consecutive immediate commands
-            if not immediate and self.releaseID < id: return
+            # Execute commands <= releaseID
+            if self.releaseID < id: return
 
             log.info('releasing id=%d' % id)
             self.q.popleft()
@@ -89,16 +78,3 @@ class CommandQueue():
         self.releaseID = id
 
         self._release()
-
-
-    def finalize(self):
-        # Mark trailing non-synchronized commands immediate
-        i = len(self.q)
-
-        while i:
-            i -= 1
-            id, synchronized, immediate, cb, args, kwargs = self.q[i]
-            if synchronized: break
-            self.q[i][2] = True
-
-        self._release()
index f42fef1f1b7ba893fabab3a8241d3a0af49ba491..beeddf37d699637062b1030fc2fbe11c65ff3ffd 100644 (file)
@@ -31,49 +31,37 @@ import logging
 import pkg_resources
 import subprocess
 import copy
-
-import bbctrl
+from pkg_resources import Requirement, resource_filename
 
 log = logging.getLogger('Config')
 
-default_config = {
-    "motors": [
-        {"axis": "X"},
-        {"axis": "Y"},
-        {"axis": "Z"},
-        {"axis": "A", "power-mode" : "disabled"},
-        ]
-    }
+
+def get_resource(path):
+    return resource_filename(Requirement.parse('bbctrl'), 'bbctrl/' + path)
 
 
 class Config(object):
     def __init__(self, ctrl):
         self.ctrl = ctrl
-        self.config_vars = {}
+        self.values = {}
 
         try:
             self.version = pkg_resources.require('bbctrl')[0].version
-            default_config['version'] = self.version
 
             # Load config template
-            with open(bbctrl.get_resource('http/config-template.json'), 'r',
+            with open(get_resource('http/config-template.json'), 'r',
                       encoding = 'utf-8') as f:
                 self.template = json.load(f)
 
-            # Add all sections from template to default config
-            for section in self.template:
-                if not section in default_config:
-                    default_config[section] = {}
-
         except Exception as e: log.exception(e)
 
 
     def get(self, name, default = None):
-        return self.config_vars.get(name, default)
+        return self.values.get(name, default)
 
 
     def get_index(self, name, index, default = None):
-        return self.config_vars.get(name, {}).get(str(index), None)
+        return self.values.get(name, {}).get(str(index), None)
 
 
     def load_path(self, path):
@@ -81,25 +69,70 @@ class Config(object):
             return json.load(f)
 
 
-    def load(self):
+    def load(self, path = 'config.json'):
         try:
-            if os.path.exists('config.json'):
-                config = self.load_path('config.json')
-            else: config = copy.deepcopy(default_config)
+            if os.path.exists(path): config = self.load_path(path)
+            else: config = {'version': self.version}
 
             try:
                 self.upgrade(config)
             except Exception as e: log.exception(e)
 
-            # Add missing sections
-            for key, value in default_config.items():
-                if not key in config: config[key] = value
-
-            return config
-
         except Exception as e:
             log.warning('%s', e)
-            return default_config
+            config = {'version': self.version}
+
+        self._defaults(config)
+        return config
+
+
+    def _valid_value(self, template, value):
+        type = template['type']
+
+        try:
+            if type == 'int':   value = int(value)
+            if type == 'float': value = float(value)
+            if type == 'text':  value = str(value)
+            if type == 'bool':  value = bool(value)
+        except:
+            return False
+
+        if (('min' in template and value < template['min']) or
+            ('max' in template and template['max'] < value) or
+            ('values' in template and value not in template['values'])):
+            return False
+
+        return True
+
+
+    def __defaults(self, config, name, template):
+        if 'type' in template:
+            if (not name in config or
+                not self._valid_value(template, config[name])):
+                config[name] = template['default']
+
+            if template['type'] == 'list':
+                config = config[name]
+
+                for i in range(len(template['index'])):
+                    if len(config) <= i: config.append({})
+
+                    for name, tmpl in template['template'].items():
+                        self.__defaults(config[i], name, tmpl)
+
+        else:
+            for name, tmpl in template.items():
+                self.__defaults(config, name, tmpl)
+
+
+    def _defaults(self, config):
+        for name, tmpl in self.template.items():
+            if not 'type' in tmpl:
+                if not name in config: config[name] = {}
+                conf = config[name]
+            else: conf = config
+
+            self.__defaults(conf, name, tmpl)
 
 
     def upgrade(self, config):
@@ -115,12 +148,26 @@ class Config(object):
                 for key in 'max-accel latch-velocity search-velocity'.split():
                     if key in motor: motor[key] /= 1000
 
+        if version <= (0, 3, 22):
+            if 'tool' in config:
+                if 'spindle-type' in config['tool']:
+                    type = config['tool']['spindle-type']
+                    if type == 'PWM': type = 'PWM Spindle'
+                    if type == 'Huanyang': type = 'Huanyang VFD'
+                    config['tool']['tool-type'] = type
+                    del config['tool']['spindle-type']
+
+                if 'spin-reversed' in config['tool']:
+                    reversed = config['tool']['spin-reversed']
+                    config['tool']['tool-reversed'] = reversed
+                    del config['tool']['spin-reversed']
+
         config['version'] = self.version
 
 
     def save(self, config):
         self.upgrade(config)
-        self.update(config)
+        self._update(config, False)
 
         with open('config.json', 'w') as f:
             json.dump(config, f)
@@ -133,49 +180,89 @@ class Config(object):
     def reset(self): os.unlink('config.json')
 
 
-    def _encode_cmd(self, name, index, value, spec):
-        if str(index):
-            if not name in self.config_vars: self.config_vars[name] = {}
-            self.config_vars[name][str(index)] = value
+    def _encode(self, name, index, config, tmpl, with_defaults):
+        # Handle category
+        if not 'type' in tmpl:
+            for name, entry in tmpl.items():
+                if 'type' in entry and config is not None:
+                    conf = config.get(name, None)
+                else: conf = config
+                self._encode(name, index, conf, entry, with_defaults)
+            return
+
+        # Handle defaults
+        if config is not None: value = config
+        elif with_defaults: value = tmpl['default']
+        else: return
 
-        else: self.config_vars[name] = value
+        # Handle list
+        if tmpl['type'] == 'list':
+            for i in range(len(tmpl['index'])):
+                if config is not None and i < len(config): conf = config[i]
+                else: conf = None
+                self._encode(name, index + tmpl['index'][i], conf,
+                             tmpl['template'], with_defaults)
+            return
 
-        if not 'code' in spec: return
+        # Update config values
+        if index:
+            if not name in self.values: self.values[name] = {}
+            self.values[name][index] = value
 
-        if spec['type'] == 'enum':
-            if value in spec['values']:
-                value = spec['values'].index(value)
-            else: value = spec['default']
+        else: self.values[name] = value
 
-        elif spec['type'] == 'bool': value = 1 if value else 0
-        elif spec['type'] == 'percent': value /= 100.0
+        # Update state variable
+        if not 'code' in tmpl: return
 
-        self.ctrl.state.config(str(index) + spec['code'], value)
+        if tmpl['type'] == 'enum':
+            if value in tmpl['values']:
+                value = tmpl['values'].index(value)
+            else: value = tmpl['default']
 
+        elif tmpl['type'] == 'bool': value = 1 if value else 0
+        elif tmpl['type'] == 'percent': value /= 100.0
 
-    def _encode_category(self, index, config, category, with_defaults):
-        for key, spec in category.items():
-            if key in config: value = config[key]
-            elif with_defaults: value = spec['default']
-            else: continue
+        self.ctrl.state.config(index + tmpl['code'], value)
 
-            self._encode_cmd(key, index, value, spec)
 
+    def _update(self, config, with_defaults):
+        for name, tmpl in self.template.items():
+            conf = config.get(name, None)
+            self._encode(name, '', conf, tmpl, with_defaults)
 
-    def _encode(self, index, config, tmpl, with_defaults):
-        for category in tmpl.values():
-            self._encode_category(index, config, category, with_defaults)
 
+    def reload(self): self._update(self.load(), True)
 
-    def update(self, config, with_defaults = False):
-        for name, tmpl in self.template.items():
-            if name == 'motors':
-                for index in range(len(config['motors'])):
-                    self._encode(index, config['motors'][index], tmpl,
-                                 with_defaults)
 
-            else: self._encode_category('', config.get(name, {}), tmpl,
-                                        with_defaults)
 
+if __name__ == "__main__":
+    import sys
+    import argparse
+
+    class State(object):
+        def config(self, name, value): print('config(%s, %s)' % (name, value))
+
+
+    class Ctrl(object):
+        def __init__(self):
+            self.state = State()
+
+    parser = argparse.ArgumentParser(description = 'Buildbotics Config Test')
+
+    parser.add_argument('configs', metavar = 'CONFIG', nargs = '*',
+                        help = 'Configuration file')
+    parser.add_argument('-u', '--update', action = 'store_true',
+                        help = 'Update config')
+    args = parser.parse_args()
+
+    config = Config(Ctrl())
+
+    def do_cfg(path):
+        cfg = config.load(path)
+        if args.update: config._update(cfg, True)
+        else: print(json.dumps(cfg, sort_keys = True, indent = 2))
+
+    if len(args.configs):
+        for path in args.configs: do_cfg(path)
 
-    def reload(self): self.update(self.load(), True)
+    else: do_cfg('')
index 02d76f033a96c3d1c61f99f29ce3fa1e9ca31561..9cf9f41fa28f8f5c5effa8525bab1fc07fc36cf8 100644 (file)
@@ -65,7 +65,7 @@ class I2C(object):
             raise e
 
 
-    def write(self, addr, cmd, byte = None, word = None):
+    def write(self, addr, cmd, byte = None, word = None, block = None):
         self.connect()
 
         try:
@@ -75,6 +75,10 @@ class I2C(object):
             elif word is not None:
                 self.i2c_bus.write_word_data(addr, cmd, word)
 
+            elif block is not None:
+                if isinstance(block, str): block = list(map(ord, block))
+                self.i2c_bus.write_i2c_block_data(addr, cmd, block)
+
             else: self.i2c_bus.write_byte(addr, cmd)
 
         except IOError as e:
index 35029b4e0ed8b558924e3e9cd243f0e78150e4bb..dc0d2a968e3c8f099a0fe29f0c6d1ed92a0fa351 100644 (file)
@@ -112,13 +112,15 @@ class Mach(Comm):
 
         if (('xx' in update or 'pr' in update) and
             self.ctrl.state.get('xx', '') == 'HOLDING'):
+            pause_reason = self.ctrl.state.get('pr', '')
+
             # Continue after seek hold
-            if (self.ctrl.state.get('pr', '') == 'Switch found' and
+            if (pause_reason == 'Switch found' and
                 self.planner.is_synchronizing()):
                 self._unpause()
 
             # Continue after stop hold
-            if self.ctrl.state.get('pr', '') == 'User stop':
+            if pause_reason == 'User stop':
                 self.planner.stop()
                 self.planner.update_position()
                 self.ctrl.state.set('line', 0)
@@ -127,6 +129,8 @@ class Mach(Comm):
 
     def _unpause(self):
         pause_reason = self.ctrl.state.get('pr', '')
+        log.info('Unpause: ' + pause_reason)
+
         if pause_reason in ['User pause', 'Switch found']:
             self.planner.restart()
 
@@ -143,6 +147,13 @@ class Mach(Comm):
         self.ctrl.state.reset()
 
 
+    def _i2c_block(self, block):
+        super().i2c_command(block[0], block = block[1:])
+
+
+    def _i2c_set(self, name, value): self._i2c_block(Cmd.set(name, value))
+
+
     @overrides(Comm)
     def comm_next(self):
         if self.planner.is_running(): return self.planner.next()
@@ -294,3 +305,18 @@ class Mach(Comm):
             self._begin_cycle('mdi')
             self.planner.set_position({axis: position})
             super().queue_command(Cmd.set_axis(axis, position))
+
+
+    def override_feed(self, override):
+        self._i2c_set('fo', int(1000 * override))
+
+
+    def override_speed(self, override):
+        self._i2c_set('so', int(1000 * override))
+
+
+    def modbus_read(self, addr): self._i2c_block(Cmd.modbus_read(addr))
+
+
+    def modbus_write(self, addr, value):
+        self._i2c_block(Cmd.modbus_write(addr, value))
index 3ce23d66d46e2311cedad6c0ccd7e1444538a8c2..bb08c9e4ba008511ef3dde2430b5c0ec5ded3e7e 100644 (file)
@@ -53,10 +53,7 @@ class Planner():
     def is_busy(self): return self.is_running() or self.cmdq.is_active()
     def is_running(self): return self.planner.is_running()
     def is_synchronizing(self): return self.planner.is_synchronizing()
-
-
-    def set_position(self, position):
-        self.planner.set_position(position)
+    def set_position(self, position): self.planner.set_position(position)
 
 
     def update_position(self):
@@ -167,7 +164,7 @@ class Planner():
 
     def _enqueue_set_cmd(self, id, name, value):
         log.info('set(#%d, %s, %s)', id, name, value)
-        self.cmdq.enqueue(id, False, self.ctrl.state.set, name, value)
+        self.cmdq.enqueue(id, self.ctrl.state.set, name, value)
 
 
     def __encode(self, block):
@@ -185,7 +182,7 @@ class Planner():
 
             if name == 'message':
                 self.cmdq.enqueue(
-                    id, False, self.ctrl.msgs.broadcast, {'message': value})
+                    id, self.ctrl.msgs.broadcast, {'message': value})
 
             if name in ['line', 'tool']:
                 self._enqueue_set_cmd(id, name, value)
@@ -193,14 +190,17 @@ class Planner():
             if name == 'speed': return Cmd.speed(value)
 
             if len(name) and name[0] == '_':
-                self._enqueue_set_cmd(id, name[1:], value)
+                # Don't queue axis positions, can be triggered by set_position()
+                if len(name) != 2 or name[1] not in 'xyzabc':
+                    self._enqueue_set_cmd(id, name[1:], value)
 
             if name[0:1] == '_' and name[1:2] in 'xyzabc':
                 if name[2:] == '_home': return Cmd.set_axis(name[1], value)
 
                 if name[2:] == '_homed':
                     motor = self.ctrl.state.find_motor(name[1])
-                    if motor is not None: return Cmd.set('%dh' % motor, value)
+                    if motor is not None:
+                        return Cmd.set_sync('%dh' % motor, value)
 
             return
 
@@ -216,6 +216,7 @@ class Planner():
         if type == 'pause': return Cmd.pause(block['pause-type'])
         if type == 'seek':
             return Cmd.seek(block['switch'], block['active'], block['error'])
+        if type == 'end': return '' # Sends id
 
         raise Exception('Unknown planner command "%s"' % type)
 
@@ -224,8 +225,8 @@ class Planner():
         cmd = self.__encode(block)
 
         if cmd is not None:
-            self.cmdq.enqueue(block['id'], True, None)
-            return Cmd.set('id', block['id']) + '\n' + cmd
+            self.cmdq.enqueue(block['id'], None)
+            return Cmd.set_sync('id', block['id']) + '\n' + cmd
 
 
     def reset(self):
@@ -268,7 +269,10 @@ class Planner():
 
             log.info('Planner restart: %d %s' % (id, json.dumps(position)))
             self.planner.restart(id, position)
-            if self.planner.is_synchronizing(): self.planner.synchronize(1)
+
+            if self.planner.is_synchronizing():
+                # TODO pass actual probed position
+                self.planner.synchronize(1) # Indicate successful probe
 
         except Exception as e:
             log.exception(e)
@@ -280,11 +284,8 @@ class Planner():
             while self.planner.has_more():
                 cmd = self.planner.next()
                 cmd = self._encode(cmd)
-                if not self.planner.is_running(): self.cmdq.finalize()
                 if cmd is not None: return cmd
 
-            self.cmdq.finalize()
-
         except Exception as e:
             log.exception(e)
             self.reset()
index d9a1332952ad49d987e176caf1935ca90bc641d0..cab3b13e5be336285d326e92a4af1ea538c80aa2 100644 (file)
@@ -289,6 +289,16 @@ class OverrideSpeedHandler(bbctrl.APIHandler):
     def put_ok(self, value): self.ctrl.mach.override_speed(float(value))
 
 
+class ModbusReadHandler(bbctrl.APIHandler):
+    def put_ok(self): self.ctrl.mach.modbus_read(int(self.json['address']))
+
+
+class ModbusWriteHandler(bbctrl.APIHandler):
+    def put_ok(self):
+        self.ctrl.mach.modbus_write(int(self.json['address']),
+                                    int(self.json['value']))
+
+
 class JogHandler(bbctrl.APIHandler):
     def put_ok(self): self.ctrl.mach.jog(self.json)
 
@@ -388,6 +398,8 @@ class Web(tornado.web.Application):
             (r'/api/position/([xyzabcXYZABC])', PositionHandler),
             (r'/api/override/feed/([\d.]+)', OverrideFeedHandler),
             (r'/api/override/speed/([\d.]+)', OverrideSpeedHandler),
+            (r'/api/modbus/read', ModbusReadHandler),
+            (r'/api/modbus/write', ModbusWriteHandler),
             (r'/api/jog', JogHandler),
             (r'/api/video/reload', VideoReloadHandler),
             (r'/(.*)', StaticFileHandler,
index 412698e5bb04390a6f2a0e3def644cda64e9a516..d985dfc019c61093696561fd5182e302626ececd 100644 (file)
 {
   "motors": {
-    "general": {
-      "axis": {
-        "type": "enum",
-        "values": ["X", "Y", "Z", "A", "B", "C"],
-        "default": "X",
-        "code": "an"
-      }
-    },
-
-    "power": {
-      "power-mode": {
-        "type": "enum",
-        "values": ["disabled", "always-on", "in-cycle", "when-moving"],
-        "default": "when-moving",
-        "code": "pm"
-      },
-      "drive-current": {
-        "type": "float",
-        "min": 0,
-        "max": 8,
-        "unit": "amps",
-        "default": 1.5,
-        "code": "dc"
+    "type": "list",
+    "index": "0123",
+    "default": [
+      {"axis": "X"},
+      {"axis": "Y"},
+      {"axis": "Z"},
+      {"axis": "A", "power-mode" : "disabled"}
+    ],
+    "template": {
+      "general": {
+        "axis": {
+          "type": "enum",
+          "values": ["X", "Y", "Z", "A", "B", "C"],
+          "default": "X",
+          "code": "an"
+        }
       },
-      "idle-current": {
-        "type": "float",
-        "min": 0,
-        "max": 8,
-        "unit": "amps",
-        "default": 0,
-        "code": "ic"
-      }
-    },
 
-    "motion": {
-      "reverse": {
-        "type": "bool",
-        "default": false,
-        "code": "rv"
-      },
-      "microsteps": {
-        "type": "int",
-        "values": [1, 2, 4, 8, 16, 32, 64, 128],
-        "unit": "per full step",
-        "default": 32,
-        "code": "mi"
+      "power": {
+        "power-mode": {
+          "type": "enum",
+          "values": ["disabled", "always-on", "in-cycle", "when-moving"],
+          "default": "when-moving",
+          "code": "pm"
+        },
+        "drive-current": {
+          "type": "float",
+          "min": 0,
+          "max": 8,
+          "unit": "amps",
+          "default": 1.5,
+          "code": "dc"
+        },
+        "idle-current": {
+          "type": "float",
+          "min": 0,
+          "max": 8,
+          "unit": "amps",
+          "default": 0,
+          "code": "ic"
+        }
       },
-      "max-velocity": {
-        "type": "float",
-        "min": 0,
-        "unit": "m/min",
-        "default": 5,
-        "code": "vm"
-      },
-      "max-accel": {
-        "type": "float",
-        "min": 0,
-        "unit": "km/min²",
-        "default": 10,
-        "code": "am"
-      },
-      "max-jerk": {
-        "type": "float",
-        "min": 0,
-        "unit": "km/min³",
-        "default": 50,
-        "code": "jm"
-      },
-      "step-angle": {
-        "type": "float",
-        "min": 0,
-        "max": 360,
-        "step": 0.1,
-        "unit": "degrees",
-        "default": 1.8,
-        "code": "sa"
-      },
-      "travel-per-rev": {
-        "type": "float",
-        "unit": "mm",
-        "default": 5,
-        "code": "tr"
-      }
-    },
 
-    "limits": {
-      "min-soft-limit": {
-        "type": "float",
-        "unit": "mm",
-        "default": 0,
-        "code": "tn"
+      "motion": {
+        "reverse": {
+          "type": "bool",
+          "default": false,
+          "code": "rv"
+        },
+        "microsteps": {
+          "type": "int",
+          "values": [1, 2, 4, 8, 16, 32, 64, 128],
+          "unit": "per full step",
+          "default": 32,
+          "code": "mi"
+        },
+        "max-velocity": {
+          "type": "float",
+          "min": 0,
+          "unit": "m/min",
+          "default": 5,
+          "code": "vm"
+        },
+        "max-accel": {
+          "type": "float",
+          "min": 0,
+          "unit": "km/min²",
+          "default": 10,
+          "code": "am"
+        },
+        "max-jerk": {
+          "type": "float",
+          "min": 0,
+          "unit": "km/min³",
+          "default": 50,
+          "code": "jm"
+        },
+        "step-angle": {
+          "type": "float",
+          "min": 0,
+          "max": 360,
+          "step": 0.1,
+          "unit": "degrees",
+          "default": 1.8,
+          "code": "sa"
+        },
+        "travel-per-rev": {
+          "type": "float",
+          "unit": "mm",
+          "default": 5,
+          "code": "tr"
+        }
       },
-      "max-soft-limit": {
-        "type": "float",
-        "unit": "mm",
-        "default": 0,
-        "code": "tm"
-      },
-      "min-switch": {
-        "type": "enum",
-        "values": ["disabled", "normally-open", "normally-closed"],
-        "default": "disabled",
-        "code": "ls"
-      },
-      "max-switch": {
-        "type": "enum",
-        "values": ["disabled", "normally-open", "normally-closed"],
-        "default": "disabled",
-        "code": "xs"
-      }
-    },
 
-    "homing": {
-      "homing-mode": {
-        "type": "enum",
-        "values": ["manual", "switch-min", "switch-max"],
-        "default": "manual",
-        "code": "ho"
-      },
-      "search-velocity": {
-        "type": "float",
-        "min": 0,
-        "unit": "m/min",
-        "default": 0.5,
-        "code": "sv"
-      },
-      "latch-velocity": {
-        "type": "float",
-        "min": 0,
-        "unit": "m/min",
-        "default": 0.1,
-        "code": "lv"
+      "limits": {
+        "min-soft-limit": {
+          "type": "float",
+          "unit": "mm",
+          "default": 0,
+          "code": "tn"
+        },
+        "max-soft-limit": {
+          "type": "float",
+          "unit": "mm",
+          "default": 0,
+          "code": "tm"
+        },
+        "min-switch": {
+          "type": "enum",
+          "values": ["disabled", "normally-open", "normally-closed"],
+          "default": "disabled",
+          "code": "ls"
+        },
+        "max-switch": {
+          "type": "enum",
+          "values": ["disabled", "normally-open", "normally-closed"],
+          "default": "disabled",
+          "code": "xs"
+        }
       },
-      "latch-backoff": {
-        "type": "float",
-        "min": 0,
-        "unit": "mm",
-        "default": 5,
-        "code": "lb"
-      },
-      "zero-backoff": {
-        "type": "float",
-        "min": 0,
-        "unit": "mm",
-        "default": 1,
-        "code": "zb"
+
+      "homing": {
+        "homing-mode": {
+          "type": "enum",
+          "values": ["manual", "switch-min", "switch-max"],
+          "default": "manual",
+          "code": "ho"
+        },
+        "search-velocity": {
+          "type": "float",
+          "min": 0,
+          "unit": "m/min",
+          "default": 0.5,
+          "code": "sv"
+        },
+        "latch-velocity": {
+          "type": "float",
+          "min": 0,
+          "unit": "m/min",
+          "default": 0.1,
+          "code": "lv"
+        },
+        "latch-backoff": {
+          "type": "float",
+          "min": 0,
+          "unit": "mm",
+          "default": 5,
+          "code": "lb"
+        },
+        "zero-backoff": {
+          "type": "float",
+          "min": 0,
+          "unit": "mm",
+          "default": 1,
+          "code": "zb"
+        }
       }
     }
   },
 
   "tool": {
-    "spindle-type": {
+    "tool-type": {
       "type": "enum",
-      "values": ["Disabled", "PWM", "Huanyang", "YL600"],
+      "values": ["Disabled", "PWM Spindle", "Huanyang VFD", "VFD Test",
+                 "Custom Modbus VFD", "YL600 VFD", "AC-Tech VFD"],
       "default": "Disabled",
       "code": "st"
     },
-    "spin-reversed": {
+    "tool-reversed": {
       "type": "bool",
-      "default": "false",
+      "default": false,
       "code": "sr"
     },
     "max-spin": {
       "default": "None",
       "code": "ma"
     },
-    "stop-bits": {
-      "type": "enum",
-      "values": ["1", "2"],
-      "default": "1",
-      "code": "ms"
+    "regs": {
+      "type": "list",
+      "index": "0123456789abcdefghijklmnopqrstuv",
+      "default": [],
+      "template": {
+        "reg-type": {
+          "type": "enum",
+          "values": [
+            "disabled",
+            "connect-write",
+            "max-freq-read", "max-freq-fixed",
+            "freq-set", "freq-signed-set",
+            "stop-write", "forward-write", "reverse-write",
+            "freq-read", "freq-signed-read",
+            "disconnect-write"],
+          "default": "disabled",
+          "code": "vt"
+        },
+        "reg-addr": {
+          "type": "int",
+          "min": 0,
+          "max": 65535,
+          "default": 0,
+          "code": "va"
+        },
+        "reg-value": {
+          "type": "int",
+          "min": 0,
+          "max": 65535,
+          "default": 0,
+          "code": "vv"
+        }
+      }
     }
   },
 
   "pwm-spindle": {
     "pwm-inverted": {
       "type": "bool",
-      "default": "false",
+      "default": false,
       "code": "pi"
     },
     "pwm-min-duty": {
     "estop": {
       "type": "enum",
       "values": ["disabled", "normally-open", "normally-closed"],
-      "default": "normally-open",
+      "default": "disabled",
       "code": "et"
     },
     "probe": {
diff --git a/src/resources/js/gauge.min.js b/src/resources/js/gauge.min.js
deleted file mode 100644 (file)
index 733d502..0000000
+++ /dev/null
@@ -1 +0,0 @@
-(function(){var a,b,c,d,e,f,g,h,i,j,k,l,m,n,o,p,q={}.hasOwnProperty,r=function(a,b){function c(){this.constructor=a}for(var d in b)q.call(b,d)&&(a[d]=b[d]);return c.prototype=b.prototype,a.prototype=new c,a.__super__=b.prototype,a};!function(){var a,b,c,d,e,f,g;for(g=["ms","moz","webkit","o"],c=0,e=g.length;e>c&&(f=g[c],!window.requestAnimationFrame);c++)window.requestAnimationFrame=window[f+"RequestAnimationFrame"],window.cancelAnimationFrame=window[f+"CancelAnimationFrame"]||window[f+"CancelRequestAnimationFrame"];return a=null,d=0,b={},requestAnimationFrame?window.cancelAnimationFrame?void 0:(a=window.requestAnimationFrame,window.requestAnimationFrame=function(c,e){var f;return f=++d,a(function(){return b[f]?void 0:c()},e),f},window.cancelAnimationFrame=function(a){return b[a]=!0}):(window.requestAnimationFrame=function(a,b){var c,d,e,f;return c=(new Date).getTime(),f=Math.max(0,16-(c-e)),d=window.setTimeout(function(){return a(c+f)},f),e=c+f,d},window.cancelAnimationFrame=function(a){return clearTimeout(a)})}(),String.prototype.hashCode=function(){var a,b,c,d,e;if(b=0,0===this.length)return b;for(c=d=0,e=this.length;e>=0?e>d:d>e;c=e>=0?++d:--d)a=this.charCodeAt(c),b=(b<<5)-b+a,b&=b;return b},o=function(a){var b,c;for(b=Math.floor(a/3600),c=Math.floor((a-3600*b)/60),a-=3600*b+60*c,a+="",c+="";c.length<2;)c="0"+c;for(;a.length<2;)a="0"+a;return b=b?b+":":"",b+c+":"+a},m=function(a){return k(a.toFixed(0))},p=function(a,b){var c,d;for(c in b)q.call(b,c)&&(d=b[c],a[c]=d);return a},n=function(a,b){var c,d,e;d={};for(c in a)q.call(a,c)&&(e=a[c],d[c]=e);for(c in b)q.call(b,c)&&(e=b[c],d[c]=e);return d},k=function(a){var b,c,d,e;for(a+="",c=a.split("."),d=c[0],e="",c.length>1&&(e="."+c[1]),b=/(\d+)(\d{3})/;b.test(d);)d=d.replace(b,"$1,$2");return d+e},l=function(a){return"#"===a.charAt(0)?a.substring(1,7):a},j=function(){function a(a,b){null==a&&(a=!0),this.clear=null!=b?b:!0,a&&AnimationUpdater.add(this)}return a.prototype.animationSpeed=32,a.prototype.update=function(a){var b;return null==a&&(a=!1),a||this.displayedValue!==this.value?(this.ctx&&this.clear&&this.ctx.clearRect(0,0,this.canvas.width,this.canvas.height),b=this.value-this.displayedValue,Math.abs(b/this.animationSpeed)<=.001?this.displayedValue=this.value:this.displayedValue=this.displayedValue+b/this.animationSpeed,this.render(),!0):!1},a}(),e=function(a){function b(){return b.__super__.constructor.apply(this,arguments)}return r(b,a),b.prototype.displayScale=1,b.prototype.setTextField=function(a){return this.textField=a instanceof i?a:new i(a)},b.prototype.setMinValue=function(a,b){var c,d,e,f,g;if(this.minValue=a,null==b&&(b=!0),b){for(this.displayedValue=this.minValue,f=this.gp||[],g=[],d=0,e=f.length;e>d;d++)c=f[d],g.push(c.displayedValue=this.minValue);return g}},b.prototype.setOptions=function(a){return null==a&&(a=null),this.options=n(this.options,a),this.textField&&(this.textField.el.style.fontSize=a.fontSize+"px"),this.options.angle>.5&&(this.gauge.options.angle=.5),this.configDisplayScale(),this},b.prototype.configDisplayScale=function(){var a,b,c,d,e;return d=this.displayScale,this.options.highDpiSupport===!1?delete this.displayScale:(b=window.devicePixelRatio||1,a=this.ctx.webkitBackingStorePixelRatio||this.ctx.mozBackingStorePixelRatio||this.ctx.msBackingStorePixelRatio||this.ctx.oBackingStorePixelRatio||this.ctx.backingStorePixelRatio||1,this.displayScale=b/a),this.displayScale!==d&&(e=this.canvas.G__width||this.canvas.width,c=this.canvas.G__height||this.canvas.height,this.canvas.width=e*this.displayScale,this.canvas.height=c*this.displayScale,this.canvas.style.width=e+"px",this.canvas.style.height=c+"px",this.canvas.G__width=e,this.canvas.G__height=c),this},b}(j),i=function(){function a(a){this.el=a}return a.prototype.render=function(a){return this.el.innerHTML=m(a.displayedValue)},a}(),a=function(a){function b(a,b){this.elem=a,this.text=null!=b?b:!1,this.value=1*this.elem.innerHTML,this.text&&(this.value=0)}return r(b,a),b.prototype.displayedValue=0,b.prototype.value=0,b.prototype.setVal=function(a){return this.value=1*a},b.prototype.render=function(){var a;return a=this.text?o(this.displayedValue.toFixed(0)):k(m(this.displayedValue)),this.elem.innerHTML=a},b}(j),b={create:function(b){var c,d,e,f;for(f=[],d=0,e=b.length;e>d;d++)c=b[d],f.push(new a(c));return f}},h=function(a){function b(a){this.gauge=a,this.ctx=this.gauge.ctx,this.canvas=this.gauge.canvas,b.__super__.constructor.call(this,!1,!1),this.setOptions()}return r(b,a),b.prototype.displayedValue=0,b.prototype.value=0,b.prototype.options={strokeWidth:.035,length:.1,color:"#000000"},b.prototype.setOptions=function(a){return null==a&&(a=null),p(this.options,a),this.length=this.canvas.height*this.options.length,this.strokeWidth=this.canvas.height*this.options.strokeWidth,this.maxValue=this.gauge.maxValue,this.minValue=this.gauge.minValue,this.animationSpeed=this.gauge.animationSpeed,this.options.angle=this.gauge.options.angle},b.prototype.render=function(){var a,b,c,d,e,f,g,h,i;return a=this.gauge.getAngle.call(this,this.displayedValue),b=this.canvas.width/2,c=.9*this.canvas.height,h=Math.round(b+this.length*Math.cos(a)),i=Math.round(c+this.length*Math.sin(a)),f=Math.round(b+this.strokeWidth*Math.cos(a-Math.PI/2)),g=Math.round(c+this.strokeWidth*Math.sin(a-Math.PI/2)),d=Math.round(b+this.strokeWidth*Math.cos(a+Math.PI/2)),e=Math.round(c+this.strokeWidth*Math.sin(a+Math.PI/2)),this.ctx.fillStyle=this.options.color,this.ctx.beginPath(),this.ctx.arc(b,c,this.strokeWidth,0,2*Math.PI,!0),this.ctx.fill(),this.ctx.beginPath(),this.ctx.moveTo(f,g),this.ctx.lineTo(h,i),this.ctx.lineTo(d,e),this.ctx.fill()},b}(j),c=function(){function a(a){this.elem=a}return a.prototype.updateValues=function(a){return this.value=a[0],this.maxValue=a[1],this.avgValue=a[2],this.render()},a.prototype.render=function(){var a,b;return this.textField&&this.textField.text(m(this.value)),0===this.maxValue&&(this.maxValue=2*this.avgValue),b=this.value/this.maxValue*100,a=this.avgValue/this.maxValue*100,$(".bar-value",this.elem).css({width:b+"%"}),$(".typical-value",this.elem).css({width:a+"%"})},a}(),g=function(a){function b(a){this.canvas=a,b.__super__.constructor.call(this),this.percentColors=null,"undefined"!=typeof G_vmlCanvasManager&&(this.canvas=window.G_vmlCanvasManager.initElement(this.canvas)),this.ctx=this.canvas.getContext("2d"),this.gp=[new h(this)],this.setOptions(),this.render()}return r(b,a),b.prototype.elem=null,b.prototype.value=[20],b.prototype.maxValue=80,b.prototype.minValue=0,b.prototype.displayedAngle=0,b.prototype.displayedValue=0,b.prototype.lineWidth=40,b.prototype.paddingBottom=.1,b.prototype.percentColors=null,b.prototype.options={colorStart:"#6fadcf",colorStop:void 0,gradientType:0,strokeColor:"#e0e0e0",pointer:{length:.8,strokeWidth:.035},angle:.15,lineWidth:.44,fontSize:40,limitMax:!1},b.prototype.setOptions=function(a){var c,d,e,f;for(null==a&&(a=null),b.__super__.setOptions.call(this,a),this.configPercentColors(),this.lineWidth=this.canvas.height*(1-this.paddingBottom)*this.options.lineWidth,this.radius=this.canvas.height*(1-this.paddingBottom)-this.lineWidth,this.ctx.clearRect(0,0,this.canvas.width,this.canvas.height),this.render(),f=this.gp,d=0,e=f.length;e>d;d++)c=f[d],c.setOptions(this.options.pointer),c.render();return this},b.prototype.configPercentColors=function(){var a,b,c,d,e,f,g;if(this.percentColors=null,void 0!==this.options.percentColors){for(this.percentColors=new Array,f=[],c=d=0,e=this.options.percentColors.length-1;e>=0?e>=d:d>=e;c=e>=0?++d:--d)g=parseInt(l(this.options.percentColors[c][1]).substring(0,2),16),b=parseInt(l(this.options.percentColors[c][1]).substring(2,4),16),a=parseInt(l(this.options.percentColors[c][1]).substring(4,6),16),f.push(this.percentColors[c]={pct:this.options.percentColors[c][0],color:{r:g,g:b,b:a}});return f}},b.prototype.set=function(a){var b,c,d,e,f,g,i;if(a instanceof Array||(a=[a]),a.length>this.gp.length)for(b=c=0,g=a.length-this.gp.length;g>=0?g>c:c>g;b=g>=0?++c:--c)this.gp.push(new h(this));for(b=0,f=!1,d=0,e=a.length;e>d;d++)i=a[d],i>this.maxValue&&(this.maxValue=1.1*this.value,f=!0),this.gp[b].value=i,this.gp[b++].setOptions({maxValue:this.maxValue,angle:this.options.angle});return this.value=a[a.length-1],f&&this.options.limitMax?void 0:AnimationUpdater.run()},b.prototype.getAngle=function(a){return(1+this.options.angle)*Math.PI+(a-this.minValue)/(this.maxValue-this.minValue)*(1-2*this.options.angle)*Math.PI},b.prototype.getColorForPercentage=function(a,b){var c,d,e,f,g,h,i;if(0===a)c=this.percentColors[0].color;else for(c=this.percentColors[this.percentColors.length-1].color,e=f=0,h=this.percentColors.length-1;h>=0?h>=f:f>=h;e=h>=0?++f:--f)if(a<=this.percentColors[e].pct){b===!0?(i=this.percentColors[e-1],d=this.percentColors[e],g=(a-i.pct)/(d.pct-i.pct),c={r:Math.floor(i.color.r*(1-g)+d.color.r*g),g:Math.floor(i.color.g*(1-g)+d.color.g*g),b:Math.floor(i.color.b*(1-g)+d.color.b*g)}):c=this.percentColors[e].color;break}return"rgb("+[c.r,c.g,c.b].join(",")+")"},b.prototype.getColorForValue=function(a,b){var c;return c=(a-this.minValue)/(this.maxValue-this.minValue),this.getColorForPercentage(c,b)},b.prototype.render=function(){var a,b,c,d,e,f,g,h,i;for(i=this.canvas.width/2,d=this.canvas.height*(1-this.paddingBottom),a=this.getAngle(this.displayedValue),this.textField&&this.textField.render(this),this.ctx.lineCap="butt",void 0!==this.options.customFillStyle?b=this.options.customFillStyle(this):null!==this.percentColors?b=this.getColorForValue(this.displayedValue,!0):void 0!==this.options.colorStop?(b=0===this.options.gradientType?this.ctx.createRadialGradient(i,d,9,i,d,70):this.ctx.createLinearGradient(0,0,i,0),b.addColorStop(0,this.options.colorStart),b.addColorStop(1,this.options.colorStop)):b=this.options.colorStart,this.ctx.strokeStyle=b,this.ctx.beginPath(),this.ctx.arc(i,d,this.radius,(1+this.options.angle)*Math.PI,a,!1),this.ctx.lineWidth=this.lineWidth,this.ctx.stroke(),this.ctx.strokeStyle=this.options.strokeColor,this.ctx.beginPath(),this.ctx.arc(i,d,this.radius,a,(2-this.options.angle)*Math.PI,!1),this.ctx.stroke(),g=this.gp,h=[],e=0,f=g.length;f>e;e++)c=g[e],h.push(c.update(!0));return h},b}(e),d=function(a){function b(a){this.canvas=a,b.__super__.constructor.call(this),"undefined"!=typeof G_vmlCanvasManager&&(this.canvas=window.G_vmlCanvasManager.initElement(this.canvas)),this.ctx=this.canvas.getContext("2d"),this.setOptions(),this.render()}return r(b,a),b.prototype.lineWidth=15,b.prototype.displayedValue=0,b.prototype.value=33,b.prototype.maxValue=80,b.prototype.minValue=0,b.prototype.options={lineWidth:.1,colorStart:"#6f6ea0",colorStop:"#c0c0db",strokeColor:"#eeeeee",shadowColor:"#d5d5d5",angle:.35},b.prototype.getAngle=function(a){return(1-this.options.angle)*Math.PI+(a-this.minValue)/(this.maxValue-this.minValue)*(2+this.options.angle-(1-this.options.angle))*Math.PI},b.prototype.setOptions=function(a){return null==a&&(a=null),b.__super__.setOptions.call(this,a),this.lineWidth=this.canvas.height*this.options.lineWidth,this.radius=this.canvas.height/2-this.lineWidth/2,this},b.prototype.set=function(a){return this.value=a,this.value>this.maxValue&&(this.maxValue=1.1*this.value),AnimationUpdater.run()},b.prototype.render=function(){var a,b,c,d,e,f;return a=this.getAngle(this.displayedValue),f=this.canvas.width/2,c=this.canvas.height/2,this.textField&&this.textField.render(this),b=this.ctx.createRadialGradient(f,c,39,f,c,70),b.addColorStop(0,this.options.colorStart),b.addColorStop(1,this.options.colorStop),d=this.radius-this.lineWidth/2,e=this.radius+this.lineWidth/2,this.ctx.strokeStyle=this.options.strokeColor,this.ctx.beginPath(),this.ctx.arc(f,c,this.radius,(1-this.options.angle)*Math.PI,(2+this.options.angle)*Math.PI,!1),this.ctx.lineWidth=this.lineWidth,this.ctx.lineCap="round",this.ctx.stroke(),this.ctx.strokeStyle=b,this.ctx.beginPath(),this.ctx.arc(f,c,this.radius,(1-this.options.angle)*Math.PI,a,!1),this.ctx.stroke()},b}(e),f=function(a){function b(){return b.__super__.constructor.apply(this,arguments)}return r(b,a),b.prototype.strokeGradient=function(a,b,c,d){var e;return e=this.ctx.createRadialGradient(a,b,c,a,b,d),e.addColorStop(0,this.options.shadowColor),e.addColorStop(.12,this.options._orgStrokeColor),e.addColorStop(.88,this.options._orgStrokeColor),e.addColorStop(1,this.options.shadowColor),e},b.prototype.setOptions=function(a){var c,d,e,f;return null==a&&(a=null),b.__super__.setOptions.call(this,a),f=this.canvas.width/2,c=this.canvas.height/2,d=this.radius-this.lineWidth/2,e=this.radius+this.lineWidth/2,this.options._orgStrokeColor=this.options.strokeColor,this.options.strokeColor=this.strokeGradient(f,c,d,e),this},b}(d),window.AnimationUpdater={elements:[],animId:null,addAll:function(a){var b,c,d,e;for(e=[],c=0,d=a.length;d>c;c++)b=a[c],e.push(AnimationUpdater.elements.push(b));return e},add:function(a){return AnimationUpdater.elements.push(a)},run:function(){var a,b,c,d,e;for(a=!0,e=AnimationUpdater.elements,c=0,d=e.length;d>c;c++)b=e[c],b.update()&&(a=!1);return a?cancelAnimationFrame(AnimationUpdater.animId):AnimationUpdater.animId=requestAnimationFrame(AnimationUpdater.run)}},"function"==typeof window.define&&null!=window.define.amd?define(function(){return{Gauge:g,Donut:f,BaseDonut:d,TextRenderer:i}}):"undefined"!=typeof module&&null!=module.exports?module.exports={Gauge:g,Donut:f,BaseDonut:d,TextRenderer:i}:(window.Gauge=g,window.Donut=f,window.BaseDonut=d,window.TextRenderer=i)}).call(this);
\ No newline at end of file
index ab213bc4de85f6830949e243684d9f3b0615d8a2..bf79bf1a5180e71bd431ffe07ee634beffc39740 100644 (file)
@@ -481,6 +481,43 @@ body
     &:hover
       opacity 0.5
 
+.modbus-program button
+  margin 0.25em 0
+
+.pure-form .modbus-regs
+  input, select
+    border none
+    box-shadow none
+    border-radius 0
+    background transparent
+    padding 0 0.5em
+    height 1.75em
+    line-height 1.75em
+
+  input
+    text-align right
+    width 6em
+
+  button
+    margin 2px
+
+  th, td
+    border 1px solid #ccc
+    line-height 1.75em
+
+  th
+    padding 0.5em
+
+  &.fixed-regs td, td.reg-index, td.modbus-status
+    padding 0 0.5em
+
+  td.reg-index, td.reg-addr, td.reg-value
+    text-align right
+
+  tr:nth-child(even)
+    background-color #f3f3f3
+
+
 .tabs
   clear both
 
@@ -531,6 +568,19 @@ body
     padding 0.5em
 
 
+.motor.slave
+  .tmpl-input-axis .units::after
+    content "(slave motor)"
+    white-space nowrap
+
+  fieldset.limits, fieldset.homing, fieldset.motion .pure-control-group,
+  fieldset.power .pure-control-group.tmpl-input-power-mode
+    display none
+
+  fieldset.motion .pure-control-group.tmpl-input-reverse
+    display inherit
+
+
 .admin-general-view, .admin-network-view
   h2:not(:first-of-type)
     margin-top 2em