From: Joseph Coffland Date: Tue, 13 Nov 2018 21:09:50 +0000 (-0800) Subject: Many 0.4.1 and 0.4.2 changes X-Git-Url: https://git.buildbotics.com/?a=commitdiff_plain;h=991f91bcfd033723990431a11e606f5d9feaee5c;p=bbctrl-firmware Many 0.4.1 and 0.4.2 changes --- diff --git a/CHANGELOG.md b/CHANGELOG.md index dc977b0..8d53fb6 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -1,6 +1,24 @@ Buildbotics CNC Controller Firmware Changelog ============================================== +## v0.4.2 + - Suppress ``Auto-creating missing tool`` warning. + - Prevent ``Stream is closed`` error. + - Suppress ``WebGL not supported`` warning. + +## v0.4.1 + - Fix toolpath view axes bug. + - Added LASER intensity view. + - Fixed reverse path planner bug. + - Video size and path view controls persistent over browser reload. + - Fixed time and progress bugs. + - Added PWM rapid auto off feature for LASER/Plasma. + - Added dynamic PWM for LASER/Plasma. + - Added motor faults table to indicators page. + - Emit error and indicate FAULT on axis for motor driver faults. + - Display axis motor FAULT on LCD. + - Fixed bug with rapid repeated unpause. + ## v0.4.0 - Increased display precision of position and motor config. - Added support for 256 microstepping. diff --git a/Makefile b/Makefile index 7364bbb..37f85c0 100644 --- a/Makefile +++ b/Makefile @@ -98,6 +98,7 @@ $(TARGET_DIR)/index.html: $(wildcard src/static/css/*) $(TARGET_DIR)/index.html: $(wildcard src/pug/templates/*) $(TARGET_DIR)/index.html: $(wildcard src/js/*) $(TARGET_DIR)/index.html: $(wildcard src/stylus/*) +$(TARGET_DIR)/index.html: src/resources/config-template.json $(TARGET_DIR)/%.html: src/pug/%.pug node_modules @mkdir -p $(shell dirname $@) diff --git a/package-lock.json b/package-lock.json index c42f3e0..01ec522 100644 --- a/package-lock.json +++ b/package-lock.json @@ -1,6 +1,6 @@ { "name": "bbctrl", - "version": "0.4.0", + "version": "0.4.2", "lockfileVersion": 1, "requires": true, "dependencies": { diff --git a/package.json b/package.json index c56b935..6f3701d 100644 --- a/package.json +++ b/package.json @@ -1,6 +1,6 @@ { "name": "bbctrl", - "version": "0.4.0", + "version": "0.4.2", "homepage": "http://buildbotics.com/", "repository": "https://github.com/buildbotics/bbctrl-firmware", "license": "GPL-3.0+", diff --git a/src/avr/src/command.c b/src/avr/src/command.c index a4c4ea7..2b31db5 100644 --- a/src/avr/src/command.c +++ b/src/avr/src/command.c @@ -201,15 +201,15 @@ bool command_callback() { if (status == STAT_OK) cmd.active = true; // Disables LCD booting message } - block = 0; // Command consumed - switch (status) { case STAT_OK: break; case STAT_NOP: break; case STAT_MACHINE_ALARMED: STATUS_WARNING(status, ""); break; - default: STATUS_ERROR(status, ""); break; + default: STATUS_ERROR(status, "%s", block); break; } + block = 0; // Command consumed + return true; } diff --git a/src/avr/src/command.def b/src/avr/src/command.def index 7416595..7296df3 100644 --- a/src/avr/src/command.def +++ b/src/avr/src/command.def @@ -31,7 +31,8 @@ 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('%', sync_speed, 1) // [offset][speed] +CMD('%', sync_speed, 1) // [offset][speed] Command synchronized speed +CMD('p', speed, 1) // [speed] Spindle speed CMD('I', input, 1) // [a|d][port][mode][timeout] Read input CMD('d', dwell, 1) // [seconds] CMD('P', pause, 1) // [type] Pause control diff --git a/src/avr/src/config.h b/src/avr/src/config.h index b96a4d3..4c2bd1f 100644 --- a/src/avr/src/config.h +++ b/src/avr/src/config.h @@ -67,7 +67,7 @@ enum { SPI_CS_X_PIN, SPI_CS_A_PIN, SPI_CS_Z_PIN, - SPIN_PWM_PIN, + PWM_PIN, SWITCH_2_PIN, RS485_RO_PIN, RS485_DI_PIN, @@ -126,7 +126,7 @@ enum { // 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 TIMER_PWM TCD1 // PWM timer (see pwm.c) #define M1_TIMER TCD0 #define M2_TIMER TCE0 @@ -154,10 +154,13 @@ enum { #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 SEGMENT_MS 4 +#define SEGMENT_TIME (SEGMENT_MS / 60000.0) // mins // DRV8711 settings +// NOTE, PWM frequency = 1 / (2 * DTIME + TBLANK + TOFF) +// We have PWM frequency = 1 / (2 * 850nS + 1uS + 6.5uS) ~= 110kHz #define DRV8711_OFF 12 #define DRV8711_BLANK (0x32 | DRV8711_BLANK_ABT_bm) #define DRV8711_DECAY (DRV8711_DECAY_DECMOD_MIXED | 16) @@ -166,13 +169,15 @@ enum { 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_TDRIVEP_500 | \ + DRV8711_DRIVE_TDRIVEN_500 | \ DRV8711_DRIVE_OCPDEG_1 | \ - DRV8711_DRIVE_OCPTH_250) + DRV8711_DRIVE_OCPTH_500) #define DRV8711_TORQUE DRV8711_TORQUE_SMPLTH_50 +// NOTE, Datasheet suggests 850ns DTIME with the optional gate resistor +// installed. See page 30 section 8.1.2 of DRV8711 datasheet. #define DRV8711_CTRL (DRV8711_CTRL_ISGAIN_10 | \ - DRV8711_CTRL_DTIME_450 | \ + DRV8711_CTRL_DTIME_850 | \ DRV8711_CTRL_EXSTALL_bm) @@ -198,9 +203,8 @@ enum { #define SERIAL_CTS_THRESH 4 -// Spindle settings -#define SPEED_QUEUE_SIZE 64 -#define SPEED_OFFSET 6 // ms +// PWM settings +#define POWER_MAX_UPDATES SEGMENT_MS // Input #define INPUT_BUFFER_LEN 128 // text buffer size (255 max) diff --git a/src/avr/src/drv8711.c b/src/avr/src/drv8711.c index ef996e1..f4fb2ca 100644 --- a/src/avr/src/drv8711.c +++ b/src/avr/src/drv8711.c @@ -61,6 +61,7 @@ typedef struct { uint8_t status; uint16_t flags; + bool reset_flags; bool stalled; drv8711_state_t state; @@ -133,7 +134,12 @@ static bool _driver_get_enabled(int driver) { } +static bool _driver_fault(int driver) {return drivers[driver].flags & 0x1f;} + + static float _driver_get_current(int driver) { + if (_driver_fault(driver)) return 0; + drv8711_driver_t *drv = &drivers[driver]; switch (drv->state) { @@ -176,15 +182,14 @@ static uint8_t _spi_next_command(uint8_t cmd) { switch (DRV8711_CMD_ADDR(command)) { case DRV8711_STATUS_REG: drv->status = spi.responses[driver]; - - if ((drv->status & drv->flags) != drv->status) - drv->flags |= drv->status; + drv->flags |= drv->status; break; case DRV8711_OFF_REG: // We read back the OFF register to test for communication failure. if ((spi.responses[driver] & 0x1ff) != DRV8711_OFF) drv->flags |= DRV8711_COMM_ERROR_bm; + else drv->flags &= ~DRV8711_COMM_ERROR_bm; break; } } @@ -202,9 +207,14 @@ static uint8_t _spi_next_command(uint8_t cmd) { switch (DRV8711_CMD_ADDR(*command)) { case DRV8711_STATUS_REG: - if (!DRV8711_CMD_IS_READ(*command)) - // Clear STATUS flags - *command = (*command & 0xf000) | (0x0fff & ~(drv->status)); + if (!DRV8711_CMD_IS_READ(*command)) { + if (drv->reset_flags) { // Clear STATUS flags + *command = (*command & 0xf000) | (0x0fff & ~drv->status); + drv->reset_flags = false; + drv->flags = 0; + + } else *command = (*command & 0xf000) | 0x0fff; // Don't clear flags + } break; case DRV8711_TORQUE_REG: // Update motor current setting @@ -349,6 +359,8 @@ void drv8711_init() { switch_id_t stall_sw = drivers[i].stall_sw; switch_set_type(stall_sw, SW_NORMALLY_OPEN); switch_set_callback(stall_sw, _stall_switch_cb); + + drivers[i].reset_flags = true; // Reset flags once on startup } switch_set_type(SW_MOTOR_FAULT, SW_NORMALLY_OPEN); @@ -435,6 +447,11 @@ float get_active_current(int driver) { bool get_motor_fault() {return motor_fault;} +void set_driver_flags(int driver, uint16_t flags) { + drivers[driver].reset_flags = true; +} + + uint16_t get_driver_flags(int driver) {return drivers[driver].flags;} @@ -497,16 +514,3 @@ void print_status_flags(uint16_t flags) { uint16_t get_status_strings(int driver) {return get_driver_flags(driver);} bool get_driver_stalled(int driver) {return drivers[driver].stalled;} - - -// Command callback -void command_mreset(int argc, char *argv[]) { - if (argc == 1) - for (int driver = 0; driver < DRIVERS; driver++) - drivers[driver].flags = 0; - - else { - int driver = atoi(argv[1]); - if (driver < DRIVERS) drivers[driver].flags = 0; - } -} diff --git a/src/avr/src/estop.c b/src/avr/src/estop.c index de822fe..20559fa 100644 --- a/src/avr/src/estop.c +++ b/src/avr/src/estop.c @@ -91,7 +91,7 @@ void estop_trigger(stat_t reason) { // Hard stop the motors and the spindle st_shutdown(); - spindle_stop(); + spindle_estop(); // Set machine state state_estop(); diff --git a/src/avr/src/exec.c b/src/avr/src/exec.c index 3736632..23373c8 100644 --- a/src/avr/src/exec.c +++ b/src/avr/src/exec.c @@ -57,9 +57,9 @@ static struct { float time; float vel; float accel; - float max_vel; float max_accel; float max_jerk; + power_update_t power_updates[2 * POWER_MAX_UPDATES]; exec_cb_t cb; } seg; } ex; @@ -106,6 +106,8 @@ void exec_set_acceleration(float a) { float exec_get_acceleration() {return ex.accel;} void exec_set_jerk(float j) {ex.jerk = j;} + + void exec_set_cb(exec_cb_t cb) {ex.cb = cb;} @@ -115,6 +117,15 @@ void exec_move_to_target(const float target[]) { isfinite(target[AXIS_B]) && isfinite(target[AXIS_C]), STAT_BAD_FLOAT); + // Prep power updates + st_prep_power(ex.seg.power_updates); + + // Shift power updates + for (unsigned i = 0; i < POWER_MAX_UPDATES; i++) { + ex.seg.power_updates[i] = ex.seg.power_updates[i + POWER_MAX_UPDATES]; + ex.seg.power_updates[i + POWER_MAX_UPDATES].state = POWER_IGNORE; + } + // Update position copy_vector(ex.position, target); @@ -146,14 +157,19 @@ stat_t _segment_exec() { // 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; + if (!v) { + exec_set_velocity(0); + exec_set_acceleration(0); + exec_set_jerk(0); + ex.seg.time = 0; + } ex.cb = ex.seg.cb; return STAT_AGAIN; } // Update velocity and accel - ex.velocity = v; - ex.accel = a; + exec_set_velocity(v); + exec_set_acceleration(a); if (t <= SEGMENT_TIME) { // Move @@ -185,14 +201,24 @@ stat_t _segment_exec() { stat_t exec_segment(float time, const float target[], float vel, float accel, - float maxVel, float maxAccel, float maxJerk) { + float maxAccel, float maxJerk, + const power_update_t power_updates[]) { ESTOP_ASSERT(time <= SEGMENT_TIME, STAT_SHORT_SEG_TIME); + // Copy power updates in to the correct position given the time offset + float nextT = ex.seg.time + time; + const float stepT = 1.0 / 60000; // 1ms in mins + float t = 0.5 / 60000; // 0.5ms in mins + unsigned j = 0; + for (unsigned i = 0; t < nextT && j < POWER_MAX_UPDATES; i++) { + if (ex.seg.time < t) ex.seg.power_updates[i] = power_updates[j++]; + t += stepT; + } + copy_vector(ex.seg.target, target); - ex.seg.time += time; + ex.seg.time = nextT; 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; diff --git a/src/avr/src/exec.h b/src/avr/src/exec.h index d139c36..af238cd 100644 --- a/src/avr/src/exec.h +++ b/src/avr/src/exec.h @@ -29,6 +29,7 @@ #include "config.h" +#include "spindle.h" #include "status.h" #include @@ -42,6 +43,7 @@ void exec_init(); void exec_get_position(float p[AXES]); float exec_get_axis_position(int axis); +float exec_get_power_scale(); void exec_set_velocity(float v); float exec_get_velocity(); void exec_set_acceleration(float a); @@ -52,5 +54,6 @@ void exec_set_cb(exec_cb_t cb); 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); + float maxAccel, float maxJerk, + const power_update_t power_updates[]); stat_t exec_next(); diff --git a/src/avr/src/huanyang.c b/src/avr/src/huanyang.c index 8c82115..4ad7ca5 100644 --- a/src/avr/src/huanyang.c +++ b/src/avr/src/huanyang.c @@ -112,7 +112,7 @@ static struct { deinit_cb_t deinit_cb; bool shutdown; bool changed; - float speed; + float power; float actual_freq; float actual_current; @@ -234,9 +234,9 @@ static void _next_command() { case 0: { // Update direction hy_ctrl_state_t state = HUANYANG_STOP; if (!hy.shutdown && !estop_triggered()) { - if (0 < hy.speed) + if (0 < hy.power) state = (hy_ctrl_state_t)(HUANYANG_RUN | HUANYANG_FORWARD); - else if (hy.speed < 0) + else if (hy.power < 0) state = (hy_ctrl_state_t)(HUANYANG_RUN | HUANYANG_REV_FWD); } @@ -250,7 +250,7 @@ static void _next_command() { case 4: { // Update freqency // Compute frequency in Hz - float freq = fabs(hy.speed * hy.max_freq); + float freq = fabs(hy.power * hy.max_freq); // Frequency write command _freq_write(freq * 100); @@ -278,9 +278,9 @@ void huanyang_deinit(deinit_cb_t cb) { } -void huanyang_set(float speed) { - if (hy.speed != speed && !hy.shutdown) { - hy.speed = speed; +void huanyang_set(float power) { + if (hy.power != power && !hy.shutdown) { + hy.power = power; hy.changed = true; } } diff --git a/src/avr/src/huanyang.h b/src/avr/src/huanyang.h index 5c51c00..b482404 100644 --- a/src/avr/src/huanyang.h +++ b/src/avr/src/huanyang.h @@ -32,7 +32,7 @@ void huanyang_init(); void huanyang_deinit(deinit_cb_t cb); -void huanyang_set(float speed); +void huanyang_set(float power); float huanyang_get(); diff --git a/src/avr/src/line.c b/src/avr/src/line.c index b1f18e6..132c14f 100644 --- a/src/avr/src/line.c +++ b/src/avr/src/line.c @@ -27,7 +27,6 @@ #include "config.h" #include "exec.h" -#include "axis.h" #include "command.h" #include "spindle.h" #include "util.h" @@ -43,7 +42,6 @@ typedef struct { float target[AXES]; float times[7]; float target_vel; - float max_vel; float max_accel; float max_jerk; @@ -52,12 +50,6 @@ typedef struct { } line_t; -typedef struct { - float time; - float speed; -} speed_t; - - static struct { line_t line; @@ -69,9 +61,9 @@ static struct { float iA; // Initial section acceleration float jerk; float lV; // Last velocity + float lD; // Last distance - float lineT; - speed_t speed; + power_update_t power_updates[POWER_MAX_UPDATES]; } l; @@ -122,30 +114,10 @@ static bool _section_next() { } -static void _load_sync_speeds(float startT, float endT) { - // Convert from mins to ms - startT *= 60000; - endT *= 60000; - - while (true) { - // Load new sync speed if needed and available - if (l.speed.time < 0 && command_peek() == COMMAND_sync_speed) - l.speed = *(speed_t *)(command_next() + 1); - - // Exit if we don't have a speed or it's not ready to be set - if (l.speed.time < 0 || endT < l.speed.time) break; - - // Queue speed - spindle_set_speed(round(l.speed.time - startT), l.speed.speed); - l.speed.time = -1; // Mark done - } -} - - static stat_t _exec_segment(float time, const float target[], float vel, float accel) { - return exec_segment(time, target, vel, accel, l.line.max_vel, - l.line.max_accel, l.line.max_jerk); + return exec_segment(time, target, vel, accel, l.line.max_accel, + l.line.max_jerk, l.power_updates); } @@ -161,9 +133,6 @@ static stat_t _line_exec() { t = section_time; } - // Handle synchronous speeds - _load_sync_speeds(l.lineT + t - seg_time, l.lineT + t); - // Compute distance and velocity float d = _segment_distance(t); float v = _segment_velocity(t); @@ -172,6 +141,10 @@ static stat_t _line_exec() { // Don't allow overshoot if (l.line.length < d) d = l.line.length; + // Handle synchronous speeds + spindle_load_power_updates(l.power_updates, l.lD, d); + l.lD = d; + // Check if section complete if (t == section_time) { if (_section_next()) { @@ -179,7 +152,6 @@ static stat_t _line_exec() { l.seg = 0; l.iD = d; l.iV = v; - l.lineT += t; } else { exec_set_cb(0); @@ -257,14 +229,6 @@ stat_t command_line(char *cmd) { 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); @@ -278,12 +242,10 @@ unsigned command_line_size() {return sizeof(line_t);} void command_line_exec(void *data) { l.line = *(line_t *)data; - l.lineT = 0; - l.speed.time = -1; - // Setup first section l.seg = 0; l.iD = 0; + l.lD = 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; @@ -310,28 +272,3 @@ void command_line_exec(void *data) { // Set callback exec_set_cb(_line_exec); } - - -stat_t command_sync_speed(char *cmd) { - speed_t s; - - cmd++; // Skip command code - - // Get target velocity - if (!decode_float(&cmd, &s.time)) return STAT_BAD_FLOAT; - if (!decode_float(&cmd, &s.speed)) return STAT_BAD_FLOAT; - - // Queue - command_push(COMMAND_sync_speed, &s); - - return STAT_OK; -} - - -unsigned command_sync_speed_size() {return sizeof(speed_t);} - - -void command_sync_speed_exec(void *data) { - speed_t s = *(speed_t *)data; - spindle_set_speed(0, s.speed); -} diff --git a/src/avr/src/pwm.c b/src/avr/src/pwm.c new file mode 100644 index 0000000..a19722a --- /dev/null +++ b/src/avr/src/pwm.c @@ -0,0 +1,221 @@ +/******************************************************************************\ + + 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 . + + 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 + . + + For information regarding this software email: + "Joseph Coffland" + +\******************************************************************************/ + +#include "pwm.h" + +#include "config.h" +#include "estop.h" +#include "outputs.h" + +#include + + +typedef struct { + bool initialized; + float freq; // base frequency for PWM driver, in Hz + float min_duty; + float max_duty; + float power; +} pwm_t; + + +static pwm_t pwm = {0}; + + +static void _set_enable(bool enable) { + outputs_set_active(TOOL_ENABLE_PIN, enable); +} + + +static void _set_dir(bool clockwise) { + outputs_set_active(TOOL_DIR_PIN, !clockwise); +} + + +static void _update_clock(uint16_t period) { + if (estop_triggered()) period = 0; + + // Disable + if (!period) { + TIMER_PWM.CTRLB = 0; // Disable clock control of pin + OUTCLR_PIN(PWM_PIN); + _set_enable(false); + return; + } + _set_enable(true); + + // 100% duty + if (period == 0xffff) { + TIMER_PWM.CTRLB = 0; // Disable clock control of pin + OUTSET_PIN(PWM_PIN); + return; + } + + // Configure clock + TIMER_PWM.CTRLB = TC1_CCAEN_bm | TC_WGMODE_SINGLESLOPE_gc; + TIMER_PWM.CCA = period; +} + + +static float _compute_duty(float power) { + power = fabsf(power); + if (!power) return 0; // 0% duty + if (power == 1 && pwm.max_duty == 1) return 1; // 100% duty + return power * (pwm.max_duty - pwm.min_duty) + pwm.min_duty; +} + + +static uint16_t _compute_period(float duty) {return TIMER_PWM.PER * duty;} + + +static void _update_pwm() { + if (pwm.initialized) + _update_clock(_compute_period(_compute_duty(pwm.power))); +} + + +static void _update_freq() { + // Set clock period and optimal prescaler value + float prescale = (F_CPU >> 16) / pwm.freq; + + if (prescale <= 1) { + TIMER_PWM.PER = F_CPU / pwm.freq; + TIMER_PWM.CTRLA = TC_CLKSEL_DIV1_gc; + + } else if (prescale <= 2) { + TIMER_PWM.PER = F_CPU / 2 / pwm.freq; + TIMER_PWM.CTRLA = TC_CLKSEL_DIV2_gc; + + } else if (prescale <= 4) { + TIMER_PWM.PER = F_CPU / 4 / pwm.freq; + TIMER_PWM.CTRLA = TC_CLKSEL_DIV4_gc; + + } else if (prescale <= 8) { + TIMER_PWM.PER = F_CPU / 8 / pwm.freq; + TIMER_PWM.CTRLA = TC_CLKSEL_DIV8_gc; + + } else if (prescale <= 64) { + TIMER_PWM.PER = F_CPU / 64 / pwm.freq; + TIMER_PWM.CTRLA = TC_CLKSEL_DIV64_gc; + + } else TIMER_PWM.CTRLA = 0; + + _update_pwm(); +} + + +void pwm_init() { + pwm.initialized = true; + pwm.power = 0; + + // Configure IO + _set_dir(true); + _set_enable(false); + _update_freq(); + + // PWM output + OUTCLR_PIN(PWM_PIN); + DIRSET_PIN(PWM_PIN); +} + + +float pwm_get() {return pwm.power;} + + +void pwm_deinit(deinit_cb_t cb) { + pwm.initialized = false; + + _set_enable(false); + + // Float PWM output pin + DIRCLR_PIN(PWM_PIN); + + // Disable clock + TIMER_PWM.CTRLA = 0; + + cb(); +} + + +power_update_t pwm_get_update(float power) { + power_update_t update = { + 0 <= power ? POWER_FORWARD : POWER_REVERSE, + power, + _compute_period(_compute_duty(power)) + }; + + return update; +} + + +// Called from hi-priority stepper interrupt, must be very fast +void pwm_update(power_update_t update) { + if (!pwm.initialized || update.state == POWER_IGNORE) return; + _update_clock(update.period); + if (update.period) _set_dir(update.state == POWER_FORWARD); + pwm.power = update.power; +} + + +// Var callbacks +float get_pwm_min_duty() {return pwm.min_duty * 100;} + + +void set_pwm_min_duty(float value) { + pwm.min_duty = value / 100; + _update_pwm(); +} + + +float get_pwm_max_duty() {return pwm.max_duty * 100;} + + +void set_pwm_max_duty(float value) { + pwm.max_duty = value / 100; + _update_pwm(); +} + + +float get_pwm_duty() {return _compute_duty(pwm.power);} +float get_pwm_freq() {return pwm.freq;} + + +void set_pwm_freq(float value) { + if (value < 8) value = 8; + if (320000 < value) value = 320000; + pwm.freq = value; + _update_freq(); +} + + +bool get_pwm_invert() {return PINCTRL_PIN(PWM_PIN) & PORT_INVEN_bm;} + + +void set_pwm_invert(bool invert) { + if (invert) PINCTRL_PIN(PWM_PIN) |= PORT_INVEN_bm; + else PINCTRL_PIN(PWM_PIN) &= ~PORT_INVEN_bm; +} diff --git a/src/avr/src/pwm.h b/src/avr/src/pwm.h new file mode 100644 index 0000000..044d811 --- /dev/null +++ b/src/avr/src/pwm.h @@ -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 . + + 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 + . + + For information regarding this software email: + "Joseph Coffland" + +\******************************************************************************/ + +#pragma once + +#include "spindle.h" + + +void pwm_init(); +float pwm_get(); +void pwm_deinit(deinit_cb_t cb); +power_update_t pwm_get_update(float power); +void pwm_update(power_update_t update); diff --git a/src/avr/src/pwm_spindle.c b/src/avr/src/pwm_spindle.c deleted file mode 100644 index b905610..0000000 --- a/src/avr/src/pwm_spindle.c +++ /dev/null @@ -1,251 +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 . - - 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 - . - - For information regarding this software email: - "Joseph Coffland" - -\******************************************************************************/ - -#include "pwm_spindle.h" - -#include "config.h" -#include "estop.h" -#include "outputs.h" - -#include - - -typedef struct { - uint8_t time; - uint16_t period; - bool clockwise; -} update_t; - - -#define RING_BUF_NAME update_q -#define RING_BUF_TYPE update_t -#define RING_BUF_INDEX_TYPE volatile uint8_t -#define RING_BUF_SIZE SPEED_QUEUE_SIZE -#include "ringbuf.def" - - -typedef struct { - float freq; // base frequency for PWM driver, in Hz - float min_duty; - float max_duty; - float duty; - float speed; - uint8_t time; -} pwm_spindle_t; - - -static pwm_spindle_t spindle = {0}; - - -static void _set_enable(bool enable) { - outputs_set_active(TOOL_ENABLE_PIN, enable); -} - - -static void _set_dir(bool clockwise) { - outputs_set_active(TOOL_DIR_PIN, !clockwise); -} - - -static void _update_clock(uint16_t period) { - if (estop_triggered()) period = 0; - - // Disable - if (!period) { - TIMER_PWM.CTRLB = 0; // Disable clock control of pin - OUTCLR_PIN(SPIN_PWM_PIN); - _set_enable(false); - return; - } - _set_enable(true); - - // 100% duty - if (period == 0xffff) { - TIMER_PWM.CTRLB = 0; // Disable clock control of pin - OUTSET_PIN(SPIN_PWM_PIN); - return; - } - - // Configure clock - TIMER_PWM.CTRLB = TC1_CCAEN_bm | TC_WGMODE_SINGLESLOPE_gc; - TIMER_PWM.CCA = period; -} - - -static float _compute_duty(float speed) { - if (!speed) return 0; // 0% duty - if (speed == 1 && spindle.max_duty == 1) return 1; // 100% duty - return speed * (spindle.max_duty - spindle.min_duty) + spindle.min_duty; -} - - -static uint16_t _compute_period(float speed) { - spindle.speed = speed; - spindle.duty = _compute_duty(speed); - - if (!spindle.duty) return 0; - if (spindle.duty == 1) return 0xffff; - return TIMER_PWM.PER * spindle.duty; -} - - -static void _update_pwm() {_update_clock(_compute_period(spindle.speed));} - - -static void _update_freq() { - // Set clock period and optimal prescaler value - float prescale = (F_CPU >> 16) / spindle.freq; - - if (prescale <= 1) { - TIMER_PWM.PER = F_CPU / spindle.freq; - TIMER_PWM.CTRLA = TC_CLKSEL_DIV1_gc; - - } else if (prescale <= 2) { - TIMER_PWM.PER = F_CPU / 2 / spindle.freq; - TIMER_PWM.CTRLA = TC_CLKSEL_DIV2_gc; - - } else if (prescale <= 4) { - TIMER_PWM.PER = F_CPU / 4 / spindle.freq; - TIMER_PWM.CTRLA = TC_CLKSEL_DIV4_gc; - - } else if (prescale <= 8) { - TIMER_PWM.PER = F_CPU / 8 / spindle.freq; - TIMER_PWM.CTRLA = TC_CLKSEL_DIV8_gc; - - } else if (prescale <= 64) { - TIMER_PWM.PER = F_CPU / 64 / spindle.freq; - TIMER_PWM.CTRLA = TC_CLKSEL_DIV64_gc; - - } else TIMER_PWM.CTRLA = 0; - - _update_pwm(); -} - - -void pwm_spindle_init() { - update_q_init(); - - // Configure IO - _set_dir(true); - _set_enable(false); - _update_freq(); - - // PWM output - OUTCLR_PIN(SPIN_PWM_PIN); - DIRSET_PIN(SPIN_PWM_PIN); -} - - -void pwm_spindle_deinit(deinit_cb_t cb) { - _set_enable(false); - - // Float PWM output pin - DIRCLR_PIN(SPIN_PWM_PIN); - - // Disable clock - TIMER_PWM.CTRLA = 0; - - cb(); -} - - -void pwm_spindle_set(uint8_t time, float speed) { - if (update_q_full()) update_q_init(); - - update_t d = { - (uint8_t)(spindle.time + time + SPEED_OFFSET), - _compute_period(fabsf(speed)), - 0 < speed - }; - - update_q_push(d); -} - - -float pwm_spindle_get() {return spindle.speed;} - - -void pwm_spindle_update() { - bool set = false; - uint16_t period; - bool clockwise; - - while (!update_q_empty()) { - update_t d = update_q_peek(); - if (spindle.time != d.time) break; - update_q_pop(); - set = true; - period = d.period; - clockwise = d.clockwise; - } - - if (set) { - _update_clock(period); - if (period) _set_dir(clockwise); - } - - spindle.time++; -} - - -// Var callbacks -float get_pwm_min_duty() {return spindle.min_duty * 100;} - - -void set_pwm_min_duty(float value) { - spindle.min_duty = value / 100; - _update_pwm(); -} - - -float get_pwm_max_duty() {return spindle.max_duty * 100;} - - -void set_pwm_max_duty(float value) { - spindle.max_duty = value / 100; - _update_pwm(); -} - - -float get_pwm_duty() {return spindle.duty;} -float get_pwm_freq() {return spindle.freq;} - - -void set_pwm_freq(float value) { - if (value < 8) value = 8; - if (320000 < value) value = 320000; - spindle.freq = value; _update_freq(); -} - - -bool get_pwm_invert() {return PINCTRL_PIN(SPIN_PWM_PIN) & PORT_INVEN_bm;} - - -void set_pwm_invert(bool invert) { - if (invert) PINCTRL_PIN(SPIN_PWM_PIN) |= PORT_INVEN_bm; - else PINCTRL_PIN(SPIN_PWM_PIN) &= ~PORT_INVEN_bm; -} diff --git a/src/avr/src/pwm_spindle.h b/src/avr/src/pwm_spindle.h deleted file mode 100644 index 5ac5e54..0000000 --- a/src/avr/src/pwm_spindle.h +++ /dev/null @@ -1,37 +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 . - - 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 - . - - For information regarding this software email: - "Joseph Coffland" - -\******************************************************************************/ - -#pragma once - -#include "spindle.h" - - -void pwm_spindle_init(); -void pwm_spindle_deinit(deinit_cb_t cb); -void pwm_spindle_set(uint8_t time, float speed); -float pwm_spindle_get(); -void pwm_spindle_update(); diff --git a/src/avr/src/spindle.c b/src/avr/src/spindle.c index 1965cae..0e5a2f1 100644 --- a/src/avr/src/spindle.c +++ b/src/avr/src/spindle.c @@ -26,139 +26,279 @@ \******************************************************************************/ #include "spindle.h" -#include "pwm_spindle.h" +#include "pwm.h" #include "huanyang.h" #include "vfd_spindle.h" +#include "stepper.h" #include "config.h" -#include "pgmspace.h" +#include "command.h" +#include "exec.h" +#include "util.h" #include +typedef struct { + float dist; + float speed; +} sync_speed_t; + + static struct { spindle_type_t type; float override; + sync_speed_t sync_speed; float speed; bool reversed; float min_rpm; float max_rpm; + bool dynamic_power; + float inv_feed; + + bool dirty; spindle_type_t next_type; } spindle = { .type = SPINDLE_TYPE_DISABLED, - .override = 1 + .override = 1, + .sync_speed = {-1, 0} }; -spindle_type_t spindle_get_type() {return spindle.type;} - - -void spindle_set_speed(uint8_t time, float speed) { - spindle.speed = speed; - +static float _speed_to_power(float 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; + if (fabs(speed) < spindle.min_rpm) speed = 0; + else if (spindle.max_rpm <= fabs(speed)) speed = negative ? -1 : 1; else speed /= spindle.max_rpm; - if (spindle.reversed) speed = -speed; - - switch (spindle.type) { - case SPINDLE_TYPE_DISABLED: break; - case SPINDLE_TYPE_PWM: pwm_spindle_set(time, speed); break; - case SPINDLE_TYPE_HUANYANG: huanyang_set(speed); break; - default: vfd_spindle_set(speed); break; - } + return spindle.reversed ? -speed : speed; } -float _get_speed() { - float speed = 0; - - switch (spindle.type) { - case SPINDLE_TYPE_DISABLED: break; - case SPINDLE_TYPE_PWM: speed = pwm_spindle_get(); break; - case SPINDLE_TYPE_HUANYANG: speed = huanyang_get(); break; - default: speed = vfd_spindle_get(); break; - } - - return speed * spindle.max_rpm; +static power_update_t _get_update() { + float power = _speed_to_power(spindle.speed); + if (spindle.dynamic_power) + power *= spindle.inv_feed ? spindle.inv_feed * exec_get_velocity() : 1; + return pwm_get_update(power); } -void spindle_stop() {spindle_set_speed(0, 0);} - +static void _set_speed(float speed) { + spindle.speed = speed; + spindle.dirty = false; -bool spindle_is_reversed() {return spindle.reversed;} + if (spindle.type == SPINDLE_TYPE_PWM) { + // PWM speed updates must be synchronized with stepper movement + power_update_t update = _get_update(); + spindle_update(update); + return; + } + float power = _speed_to_power(speed); -void spindle_update() { - if (spindle.type == SPINDLE_TYPE_PWM) pwm_spindle_update(); + switch (spindle.type) { + case SPINDLE_TYPE_DISABLED: break; + case SPINDLE_TYPE_HUANYANG: huanyang_set(power); break; + default: vfd_spindle_set(power); break; + } } -static void _update_speed() {spindle_set_speed(0, spindle.speed);} - - static void _deinit_cb() { spindle.type = spindle.next_type; spindle.next_type = SPINDLE_TYPE_DISABLED; switch (spindle.type) { case SPINDLE_TYPE_DISABLED: break; - case SPINDLE_TYPE_PWM: pwm_spindle_init(); break; + case SPINDLE_TYPE_PWM: pwm_init(); break; case SPINDLE_TYPE_HUANYANG: huanyang_init(); break; default: vfd_spindle_init(); break; } - spindle_set_speed(0, spindle.speed); + spindle.dirty = true; } -// Var callbacks -uint8_t get_tool_type() {return spindle.type;} - - -void set_tool_type(uint8_t value) { - if (value == spindle.type) return; +static void _set_type(spindle_type_t type) { + if (type == spindle.type) return; spindle_type_t old_type = spindle.type; - spindle.next_type = (spindle_type_t)value; + spindle.next_type = type; spindle.type = SPINDLE_TYPE_DISABLED; switch (old_type) { case SPINDLE_TYPE_DISABLED: _deinit_cb(); break; - case SPINDLE_TYPE_PWM: pwm_spindle_deinit(_deinit_cb); break; + case SPINDLE_TYPE_PWM: pwm_deinit(_deinit_cb); break; case SPINDLE_TYPE_HUANYANG: huanyang_deinit(_deinit_cb); break; default: vfd_spindle_deinit(_deinit_cb); break; } } -float get_speed() {return _get_speed();} -void set_speed(float speed) {spindle_set_speed(0, speed);} +spindle_type_t spindle_get_type() {return spindle.type;} + + +void spindle_load_power_updates(power_update_t updates[], float minD, + float maxD) { + float stepD = (maxD - minD) * (1.0 / POWER_MAX_UPDATES); + float d = minD + 1e-3; // Starting distance + + for (unsigned i = 0; i < POWER_MAX_UPDATES; i++) { + bool set = false; + + d += stepD; // Ending distance for this power step + updates[i].state = POWER_IGNORE; + + while (true) { + // Load new sync speed if needed and available + if (spindle.sync_speed.dist < 0 && command_peek() == COMMAND_sync_speed) + spindle.sync_speed = *(sync_speed_t *)(command_next() + 1); + + // Exit if we don't have a speed or it's not ready to be set + if (spindle.sync_speed.dist < 0 || d < spindle.sync_speed.dist) break; + + set = true; + spindle.speed = spindle.sync_speed.speed; + spindle.sync_speed.dist = -1; // Mark done + } + + // Prep power update + if (spindle.type == SPINDLE_TYPE_PWM) updates[i] = _get_update(); + else if (set) _set_speed(spindle.speed); // Set speed now for non-PWM + } +} + + +void spindle_update(power_update_t update) {return pwm_update(update);} + + +static void _flush_sync_speeds() { + spindle.sync_speed.dist = -1; + while (command_peek() == COMMAND_sync_speed) command_next(); +} + + +// Called from lo-level stepper interrupt +void spindle_idle() { + if (spindle.dirty) _set_speed(spindle.speed); + _flush_sync_speeds(); // Flush speeds in case we are holding there are more +} + + +float spindle_get_speed() { + float speed = 0; + + switch (spindle.type) { + case SPINDLE_TYPE_DISABLED: break; + case SPINDLE_TYPE_PWM: speed = pwm_get(); break; + case SPINDLE_TYPE_HUANYANG: speed = huanyang_get(); break; + default: speed = vfd_spindle_get(); break; + } + + return speed * spindle.max_rpm; +} + + +void spindle_stop() { + _flush_sync_speeds(); + _set_speed(0); +} + + +void spindle_estop() {_set_type(SPINDLE_TYPE_DISABLED);} +bool spindle_is_reversed() {return spindle.reversed;} + + +// Var callbacks +uint8_t get_tool_type() {return spindle.type;} +void set_tool_type(uint8_t value) {_set_type((spindle_type_t)value);} +float get_speed() {return spindle_get_speed();} bool get_tool_reversed() {return spindle.reversed;} void set_tool_reversed(bool reversed) { if (spindle.reversed != reversed) { spindle.reversed = reversed; - _update_speed(); + spindle.dirty = true; } } float get_max_spin() {return spindle.max_rpm;} -void set_max_spin(float value) {spindle.max_rpm = value; _update_speed();} +void set_max_spin(float value) {spindle.max_rpm = value; spindle.dirty = true;} float get_min_spin() {return spindle.min_rpm;} -void set_min_spin(float value) {spindle.min_rpm = value; _update_speed();} +void set_min_spin(float value) {spindle.min_rpm = value; spindle.dirty = true;} uint16_t get_speed_override() {return spindle.override * 1000;} void set_speed_override(uint16_t value) { spindle.override = value / 1000.0; - _update_speed(); + spindle.dirty = true; +} + + +bool get_dynamic_power() {return spindle.dynamic_power;} + + +void set_dynamic_power(bool enable) { + if (spindle.dynamic_power == enable) return; + spindle.dynamic_power = enable; + spindle.dirty = true; } + + +float get_inverse_feed() {return spindle.inv_feed;} + + +void set_inverse_feed(float iF) { + if (spindle.inv_feed == iF) return; + spindle.inv_feed = iF; + spindle.dirty = true; +} + + +// Command callbacks +stat_t command_sync_speed(char *cmd) { + sync_speed_t s; + + cmd++; // Skip command code + + // Get distance and speed + if (!decode_float(&cmd, &s.dist)) return STAT_BAD_FLOAT; + if (!decode_float(&cmd, &s.speed)) return STAT_BAD_FLOAT; + + // Queue + command_push(COMMAND_sync_speed, &s); + + return STAT_OK; +} + + +unsigned command_sync_speed_size() {return sizeof(sync_speed_t);} + + +void command_sync_speed_exec(void *data) { + spindle.sync_speed.dist = -1; // Flush any left over + _set_speed(((sync_speed_t *)data)->speed); +} + + +stat_t command_speed(char *cmd) { + cmd++; // Skip command code + + // Get speed + float speed; + if (!decode_float(&cmd, &speed)) return STAT_BAD_FLOAT; + + // Queue + command_push(COMMAND_speed, &speed); + + return STAT_OK; +} + + +unsigned command_speed_size() {return sizeof(float);} +void command_speed_exec(void *data) {_set_speed(*(float *)data);} diff --git a/src/avr/src/spindle.h b/src/avr/src/spindle.h index 7626f41..94de062 100644 --- a/src/avr/src/spindle.h +++ b/src/avr/src/spindle.h @@ -31,6 +31,20 @@ #include +typedef enum { + POWER_IGNORE, + POWER_FORWARD, + POWER_REVERSE +} power_state_t; + + +typedef struct { + power_state_t state; + float power; + uint16_t period; // Used by PWM +} power_update_t; + + typedef enum { SPINDLE_TYPE_DISABLED, SPINDLE_TYPE_PWM, @@ -47,7 +61,11 @@ typedef void (*deinit_cb_t)(); spindle_type_t spindle_get_type(); +float spindle_get_speed(); void spindle_stop(); +void spindle_estop(); bool spindle_is_reversed(); -void spindle_update(); -void spindle_set_speed(uint8_t time, float speed); +void spindle_load_power_updates(power_update_t updates[], float minD, + float maxD); +void spindle_update(power_update_t update); +void spindle_idle(); diff --git a/src/avr/src/status.c b/src/avr/src/status.c index 702eda5..f1aaa11 100644 --- a/src/avr/src/status.c +++ b/src/avr/src/status.c @@ -72,13 +72,17 @@ stat_t status_message_P(const char *location, status_level_t level, status_level_pgmstr(level)); // Message + printf_P(PSTR("%" PRPSTR), status_to_pgmstr(code)); + if (msg && pgm_read_byte(msg)) { + putchar(':'); + putchar(' '); + // TODO escape invalid chars va_start(args, msg); vfprintf_P(stdout, msg, args); va_end(args); - - } else printf_P(PSTR("%" PRPSTR), status_to_pgmstr(code)); + } putchar('"'); diff --git a/src/avr/src/stepper.c b/src/avr/src/stepper.c index 6e6904a..167a38e 100644 --- a/src/avr/src/stepper.c +++ b/src/avr/src/stepper.c @@ -34,7 +34,6 @@ #include "util.h" #include "cpp_magic.h" #include "exec.h" -#include "spindle.h" #include "drv8711.h" #include @@ -53,6 +52,8 @@ typedef struct { bool busy; bool requesting; float dwell; + uint8_t power_index; + power_update_t powers[POWER_MAX_UPDATES]; // Move prep bool move_ready; // prepped move ready for loader @@ -60,11 +61,13 @@ typedef struct { move_type_t move_type; float prep_dwell; + power_update_t prep_powers[POWER_MAX_UPDATES]; + uint32_t underflow; } stepper_t; -static volatile stepper_t st = {0}; +static stepper_t st = {0}; void stepper_init() { @@ -111,7 +114,11 @@ ISR(STEP_LOW_LEVEL_ISR) { stat_t status = exec_next(); switch (status) { - case STAT_NOP: st.busy = false; break; // No command executed + case STAT_NOP: // No move executed, idle + spindle_idle(); + st.busy = false; + break; + case STAT_AGAIN: continue; // No command executed, try again case STAT_OK: // Move executed @@ -142,11 +149,18 @@ static void _request_exec_move() { } +static void _update_power() { + if (st.power_index < POWER_MAX_UPDATES) + spindle_update(st.powers[st.power_index++]); +} + + /// Dwell or dequeue and load next move. static void _load_move() { static uint8_t tick = 0; - spindle_update(); + // Update spindle power on every tick + _update_power(); // Dwell if (0 < st.dwell) { @@ -161,7 +175,7 @@ static void _load_move() { if (exec_get_velocity()) st.underflow++; _request_exec_move(); _end_move(); - tick = 0; + tick = 0; // Try again in 1ms return; } @@ -178,6 +192,11 @@ static void _load_move() { // Start dwell st.dwell = st.prep_dwell; + // Copy power updates + st.power_index = 0; + memcpy(st.powers, st.prep_powers, sizeof(st.powers)); + _update_power(); + // We are done with this move st.move_type = MOVE_TYPE_NULL; st.prep_dwell = 0; // clear dwell @@ -193,6 +212,12 @@ static void _load_move() { ISR(STEP_TIMER_ISR) {_load_move();} +void st_prep_power(const power_update_t powers[]) { + ESTOP_ASSERT(!st.move_ready, STAT_STEPPER_NOT_READY); + memcpy(st.prep_powers, powers, sizeof(st.prep_powers)); +} + + void st_prep_line(const float target[]) { // Trap conditions that would prevent queuing the line ESTOP_ASSERT(!st.move_ready, STAT_STEPPER_NOT_READY); diff --git a/src/avr/src/stepper.h b/src/avr/src/stepper.h index f3ec277..210c85a 100644 --- a/src/avr/src/stepper.h +++ b/src/avr/src/stepper.h @@ -27,6 +27,8 @@ #pragma once +#include "spindle.h" + #include #include @@ -35,5 +37,7 @@ void stepper_init(); void st_shutdown(); void st_enable(); bool st_is_busy(); +void st_set_power_scale(float scale); +void st_prep_power(const power_update_t powers[]); void st_prep_line(const float target[]); void st_prep_dwell(float seconds); diff --git a/src/avr/src/vars.c b/src/avr/src/vars.c index 888c350..e6fe699 100644 --- a/src/avr/src/vars.c +++ b/src/avr/src/vars.c @@ -229,6 +229,12 @@ static char *_resolve_name(const char *_name) { } +static int _index(char c, const char *s) { + char *index = strchr(s, c); + return index ? index - s : -1; +} + + static bool _find_var(const char *_name, var_info_t *info) { char *name = _resolve_name(_name); if (!name) return false; @@ -238,14 +244,14 @@ static bool _find_var(const char *_name, var_info_t *info) { strcpy(info->name, name); #define VAR(NAME, CODE, TYPE, INDEX, SET, ...) \ - if (!strcmp(IF_ELSE(INDEX)(name + 1, name), #CODE)) { \ - IF(INDEX) \ - (i = strchr(INDEX##_LABEL, name[0]) - INDEX##_LABEL; \ - if (i < 0) return false); \ + if (!strcmp(IF_ELSE(INDEX)(name + 1, name), #CODE) \ + IF(INDEX)(&& (i = _index(name[0], INDEX##_LABEL)) != -1) \ + ) { \ \ info->type = TYPE_##TYPE; \ info->index = i; \ - info->get.IF_ELSE(INDEX)(get_##TYPE##_index, get_##TYPE) = get_##NAME; \ + info->get.IF_ELSE(INDEX)(get_##TYPE##_index, get_##TYPE) = \ + get_##NAME; \ \ IF(SET)(info->set.IF_ELSE(INDEX) \ (set_##TYPE##_index, set_##TYPE) = set_##NAME;) \ diff --git a/src/avr/src/vars.def b/src/avr/src/vars.def index bd0ab9d..52c4258 100644 --- a/src/avr/src/vars.def +++ b/src/avr/src/vars.def @@ -53,7 +53,7 @@ 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(driver_flags, df, u16, MOTORS, 1, 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 @@ -84,7 +84,7 @@ VAR(analog_input, ai, f32, ANALOG, 0, 0) // Analog input pins // Spindle VAR(tool_type, st, u8, 0, 1, 1) // See spindle.c -VAR(speed, s, f32, 0, 1, 1) // Current spindle speed +VAR(speed, s, f32, 0, 0, 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 @@ -132,6 +132,8 @@ 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(dynamic_power, dp, b8, 0, 1, 1) // Dynamic power +VAR(inverse_feed, if, f32, 0, 1, 1) // Inverse feed rate 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 diff --git a/src/avr/src/vfd_spindle.c b/src/avr/src/vfd_spindle.c index 591d96f..74d55d7 100644 --- a/src/avr/src/vfd_spindle.c +++ b/src/avr/src/vfd_spindle.c @@ -84,7 +84,7 @@ const vfd_reg_t ac_tech_regs[] PROGMEM = { {REG_FWD_WRITE, 1, 8}, // Start drive {REG_REV_WRITE, 1, 64}, // Reverse {REG_REV_WRITE, 1, 8}, // Start drive - {REG_FREQ_ACTECH_READ, 24, 0}, // Actual speed + {REG_FREQ_ACTECH_READ, 24, 0}, // Actual freq {REG_DISCONNECT_WRITE, 1, 2}, // Lock controls and parameters {REG_DISABLED}, }; @@ -139,9 +139,9 @@ static struct { bool changed; bool shutdown; - float speed; + float power; uint16_t max_freq; - float actual_speed; + float actual_power; uint16_t status; uint32_t wait; @@ -159,13 +159,13 @@ static void _disconnected() { static bool _next_state() { switch (vfd.state) { case REG_MAX_FREQ_FIXED: - if (!vfd.speed) vfd.state = REG_STOP_WRITE; + if (!vfd.power) vfd.state = REG_STOP_WRITE; else vfd.state = REG_FREQ_SET; break; case REG_FREQ_SIGN_SET: - if (vfd.speed < 0) vfd.state = REG_REV_WRITE; - else if (0 < vfd.speed) vfd.state = REG_FWD_WRITE; + if (vfd.power < 0) vfd.state = REG_REV_WRITE; + else if (0 < vfd.power) vfd.state = REG_FWD_WRITE; else vfd.state = REG_STOP_WRITE; break; @@ -239,14 +239,14 @@ static void _modbus_cb(bool ok, uint16_t addr, uint16_t value) { 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_READ: vfd.actual_power = value / (float)vfd.max_freq; break; case REG_FREQ_SIGN_READ: - vfd.actual_speed = (int16_t)value / (float)vfd.max_freq; + vfd.actual_power = (int16_t)value / (float)vfd.max_freq; break; case REG_FREQ_ACTECH_READ: - if (vfd.read_count == 2) vfd.actual_speed = value / (float)vfd.max_freq; + if (vfd.read_count == 2) vfd.actual_power = value / (float)vfd.max_freq; if (vfd.read_count < 6) return; break; @@ -275,12 +275,12 @@ static bool _exec_command() { case REG_FREQ_SET: write = true; - reg.value = fabs(vfd.speed) * vfd.max_freq; + reg.value = fabs(vfd.power) * vfd.max_freq; break; case REG_FREQ_SIGN_SET: write = true; - reg.value = vfd.speed * vfd.max_freq; + reg.value = vfd.power * vfd.max_freq; break; case REG_CONNECT_WRITE: @@ -346,15 +346,15 @@ void vfd_spindle_deinit(deinit_cb_t cb) { } -void vfd_spindle_set(float speed) { - if (vfd.speed != speed) { - vfd.speed = speed; +void vfd_spindle_set(float power) { + if (vfd.power != power) { + vfd.power = power; vfd.changed = true; } } -float vfd_spindle_get() {return vfd.actual_speed;} +float vfd_spindle_get() {return vfd.actual_power;} void vfd_spindle_rtc_callback() { diff --git a/src/avr/src/vfd_spindle.h b/src/avr/src/vfd_spindle.h index 17de4f6..aa6950b 100644 --- a/src/avr/src/vfd_spindle.h +++ b/src/avr/src/vfd_spindle.h @@ -32,6 +32,6 @@ void vfd_spindle_init(); void vfd_spindle_deinit(deinit_cb_t cb); -void vfd_spindle_set(float speed); +void vfd_spindle_set(float power); float vfd_spindle_get(); void vfd_spindle_rtc_callback(); diff --git a/src/js/app.js b/src/js/app.js index 913145e..c8f4e5e 100644 --- a/src/js/app.js +++ b/src/js/app.js @@ -28,6 +28,7 @@ 'use strict' var api = require('./api'); +var cookie = require('./cookie')('bbctrl-'); var Sock = require('./sock'); @@ -93,7 +94,7 @@ module.exports = new Vue({ }, state: {}, messages: [], - video_size: 'small', + video_size: cookie.get('video-size', 'small'), errorTimeout: 30, errorTimeoutStart: 0, errorShow: false, @@ -209,6 +210,7 @@ module.exports = new Vue({ toggle_video: function () { if (this.video_size == 'small') this.video_size = 'large'; else if (this.video_size == 'large') this.video_size = 'small'; + cookie.set('video-size', this.video_size); }, diff --git a/src/js/axis-vars.js b/src/js/axis-vars.js index ffa0d4f..c86b224 100644 --- a/src/js/axis-vars.js +++ b/src/js/axis-vars.js @@ -78,9 +78,15 @@ module.exports = { var klass = (homed ? 'homed' : 'unhomed') + ' axis-' + axis; var state = 'UNHOMED'; var icon = 'question-circle'; + var fault = this.state[motor_id + 'df'] & 0x1f; var title; - if (0 < dim && dim < pathDim) { + if (fault) { + state = 'FAULT'; + klass += ' error'; + icon = 'exclamation-circle'; + + } else if (0 < dim && dim < pathDim) { state = 'NO FIT'; klass += ' error'; icon = 'ban'; @@ -114,6 +120,14 @@ module.exports = { title = 'Tool path dimensions exceed axis dimensions by ' + this._length_str(pathDim - dim) + '.'; break; + + case 'FAULT': + title = 'Motor driver fault. A potentially damaging electrical ' + + 'condition was detected and the motor driver was shutdown. ' + + 'Please power down the controller and check your motor cabling. ' + + 'See the "Motor Faults" table on the "Indicators" for more ' + + 'information.'; + break; } return { diff --git a/src/js/console.js b/src/js/console.js index 80659b7..52e0cd3 100644 --- a/src/js/console.js +++ b/src/js/console.js @@ -29,7 +29,7 @@ function _msg_equal(a, b) { - return a.level == b.level && a.location == b.location && a.code == b.code && + return a.level == b.level && a.source == b.source && a.where == b.where && a.msg == b.msg; } @@ -61,7 +61,6 @@ module.exports = { var repeat = messages.length && _msg_equal(msg, messages[0]); if (repeat) messages[0].repeat++; else { - msg.repeat = 1; messages.unshift(msg); while (256 < messages.length) messages.pop(); } diff --git a/src/js/control-view.js b/src/js/control-view.js index 87065c4..25e910c 100644 --- a/src/js/control-view.js +++ b/src/js/control-view.js @@ -143,9 +143,15 @@ module.exports = { plan_time: function () {return this.state.plan_time}, + plan_time_remaining: function () { + if (!(this.is_stopping || this.is_running || this.is_holding)) return 0; + return this.toolpath.time - this.plan_time + }, + + eta: function () { if (this.mach_state != 'RUNNING') return ''; - var remaining = this.toolpath.time - this.plan_time; + var remaining = this.plan_time_remaining; var d = new Date(); d.setSeconds(d.getSeconds() + remaining); return d.toLocaleString(); @@ -153,7 +159,7 @@ module.exports = { progress: function () { - if (!this.toolpath.time) return 0; + if (!this.toolpath.time || this.is_ready) return 0; var p = this.plan_time / this.toolpath.time; return p < 1 ? p : 1; } @@ -192,7 +198,8 @@ module.exports = { load: function () { var file = this.state.selected; - if (this.last_file == file) return; + if (this.last_file == file || typeof file == 'undefined' || + typeof file == 'null') return; this.last_file = file; if (typeof file != 'undefined') this.$broadcast('gcode-load', file); @@ -205,7 +212,7 @@ module.exports = { load_toolpath: function (file) { this.toolpath = {}; - if (typeof file == 'undefined') return; + if (typeof file == 'undefined' || typeof file == 'null') return; api.get('path/' + file).done(function (toolpath) { if (this.last_file != file) return; @@ -238,7 +245,12 @@ module.exports = { load_history: function (index) {this.mdi = this.history[index];}, - open: function (e) {$('.gcode-file-input').click()}, + + + open: function (e) { + // TODO browser caches file if name is same even if contents changed + $('.gcode-file-input').click(); + }, upload: function (e) { @@ -252,6 +264,7 @@ module.exports = { api.upload('file', fd) .done(function () { + this.last_file = undefined; // Force reload this.$broadcast('gcode-reload', file.name); this.update(); }.bind(this)); diff --git a/src/js/cookie.js b/src/js/cookie.js new file mode 100644 index 0000000..6244436 --- /dev/null +++ b/src/js/cookie.js @@ -0,0 +1,69 @@ +/******************************************************************************\ + + Copyright 2018. Buildbotics LLC + All Rights Reserved. + + For information regarding this software email: + Joseph Coffland + joseph@buildbotics.com + + This software is free software: you clan redistribute it and/or + modify it under the terms of the GNU Lesser General Public License + as published by the Free Software Foundation, either version 2.1 of + the License, or (at your option) any later version. + + This 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 C! library. If not, see + . + +\******************************************************************************/ + +'use strict' + + +module.exports = function (prefix) { + if (typeof prefix == 'undefined') prefix = ''; + + var cookie = { + get: function (name, defaultValue) { + var decodedCookie = decodeURIComponent(document.cookie); + var ca = decodedCookie.split(';'); + name = prefix + name + '='; + + for (var i = 0; i < ca.length; i++) { + var c = ca[i]; + while (c.charAt(0) == ' ') c = c.substring(1); + if (!c.indexOf(name)) return c.substring(name.length, c.length); + } + + return defaultValue; + }, + + + set: function (name, value, days) { + var offset = 2147483647; // Max value + if (typeof days != 'undefined') offset = days * 24 * 60 * 60 * 1000; + var d = new Date(); + d.setTime(d.getTime() + offset); + var expires = 'expires=' + d.toUTCString(); + document.cookie = prefix + name + '=' + value + ';' + expires + ';path=/'; + }, + + + set_bool: function (name, value) { + cookie.set(name, value ? 'true' : 'false'); + }, + + + get_bool: function (name, defaultValue) { + return cookie.get(name, defaultValue ? 'true' : 'false') == 'true'; + } + } + + return cookie; +} diff --git a/src/js/gcode-viewer.js b/src/js/gcode-viewer.js index 67847e4..bbae51a 100644 --- a/src/js/gcode-viewer.js +++ b/src/js/gcode-viewer.js @@ -73,7 +73,8 @@ module.exports = { methods: { load: function (file) { - if (file == this.file) return; + if (file == this.file || typeof file == 'undefined' || + typeof file == 'null') return; this.clear(); this.file = file; diff --git a/src/js/indicators.js b/src/js/indicators.js index 15e8f08..e9881b1 100644 --- a/src/js/indicators.js +++ b/src/js/indicators.js @@ -77,6 +77,31 @@ module.exports = { case 2: return 10; case 3: return 12; } + }, + + + motor_fault_class: function (motor, fault) { + if (typeof motor == 'undefined') { + var status = this.state['fa']; + if (typeof status == 'undefined') return 'fa-question'; + return 'fa-thumbs-' + (status ? 'down error' : 'up success') + } + + var status = this.state[motor + 'ds']; + if (typeof status == 'undefined') return 'fa-question'; + return status.indexOf(fault) == -1 ? 'fa-thumbs-up success' : + 'fa-thumbs-down error'; + }, + + + motor_reset: function (motor) { + if (typeof motor == 'undefined') { + var cmd = ''; + for (var i = 0; i < 4; i++) + cmd += '\\$' + i + 'df=0\n'; + this.$dispatch('send', cmd); + + } else this.$dispatch('send', '\\$' + motor + 'df=0'); } } } diff --git a/src/js/main.js b/src/js/main.js index 58be6fa..336a306 100644 --- a/src/js/main.js +++ b/src/js/main.js @@ -77,17 +77,17 @@ $(function() { var parts = []; if (DAY <= value) { - parts.push(value / DAY); + parts.push(Math.floor(value / DAY)); value %= DAY; } if (HR <= value) { - parts.push(value / HR); + parts.push(Math.floor(value / HR)); value %= HR; } if (MIN <= value) { - parts.push(value / MIN); + parts.push(Math.floor(value / MIN)); value %= MIN; } else parts.push(0); diff --git a/src/js/path-viewer.js b/src/js/path-viewer.js index 0ceed82..2ac7082 100644 --- a/src/js/path-viewer.js +++ b/src/js/path-viewer.js @@ -26,6 +26,7 @@ 'use strict' var orbit = require('./orbit'); +var cookie = require('./cookie')('bbctrl-'); function get(obj, name, defaultValue) { @@ -48,16 +49,16 @@ module.exports = { data: function () { return { - enabled: true, + enabled: false, loading: false, - small: true, + snapView: cookie.get('snap-view', 'isometric'), + small: cookie.get_bool('small-path-view', true), surfaceMode: 'cut', - showPath: true, - showTool: true, - showBBox: true, - showAxes: true, - error: false, - message: '' + showPath: cookie.get_bool('show-path', true), + showTool: cookie.get_bool('show-tool', true), + showBBox: cookie.get_bool('show-bbox', true), + showAxes: cookie.get_bool('show-axes', true), + showIntensity: cookie.get_bool('show-intensity', false) } }, @@ -71,15 +72,42 @@ module.exports = { watch: { toolpath: function () {Vue.nextTick(this.update)}, surfaceMode: function (mode) {this.update_surface_mode(mode)}, - small: function () {Vue.nextTick(this.update_view)}, - showPath: function (enable) {set_visible(this.path, enable)}, - showTool: function (enable) {set_visible(this.tool, enable)}, - showAxes: function (enable) {set_visible(this.axes, enable)}, + + + small: function (enable) { + cookie.set_bool('small-path-view', enable); + Vue.nextTick(this.update_view) + }, + + + showPath: function (enable) { + cookie.set_bool('show-path', enable); + set_visible(this.pathView, enable) + }, + + + showTool: function (enable) { + cookie.set_bool('show-tool', enable); + set_visible(this.toolView, enable) + }, + + + showAxes: function (enable) { + cookie.set_bool('show-axes', enable); + set_visible(this.axesView, enable) + }, + + + showIntensity: function (enable) { + cookie.set_bool('show-intensity', enable); + Vue.nextTick(this.update) + }, showBBox: function (enable) { - set_visible(this.bbox, enable); - set_visible(this.envelope, enable); + cookie.set_bool('show-bbox', enable); + set_visible(this.bboxView, enable); + set_visible(this.envelopeView, enable); }, @@ -100,15 +128,13 @@ module.exports = { if (!this.enabled) return; // Reset message - this.message = '' - this.error = false; this.loading = !this.hasPath; // Update scene this.scene = new THREE.Scene(); if (this.hasPath) { this.draw(this.scene); - this.snap('isometric'); + this.snap(this.snapView); } this.update_view(); @@ -166,7 +192,7 @@ module.exports = { update_tool: function (tool) { if (!this.enabled) return; - if (typeof tool == 'undefined') tool = this.tool; + if (typeof tool == 'undefined') tool = this.toolView; if (typeof tool == 'undefined') return; tool.position.x = this.x.pos; tool.position.y = this.y.pos; @@ -176,7 +202,7 @@ module.exports = { update_envelope: function (envelope) { if (!this.enabled || !this.axes.homed) return; - if (typeof envelope == 'undefined') envelope = this.envelope; + if (typeof envelope == 'undefined') envelope = this.envelopeView; if (typeof envelope == 'undefined') return; var min = new THREE.Vector3(); @@ -209,12 +235,10 @@ module.exports = { this.target.appendChild(this.renderer.domElement); } catch (e) { - console.log(e); - this.error = true; - this.message = 'WebGL not supported'; - this.enabled = false; + console.log('WebGL not supported: ', e); return; } + this.enabled = true; // Camera this.camera = new THREE.PerspectiveCamera(45, 4 / 3, 1, 1000); @@ -247,7 +271,6 @@ module.exports = { this.controls.dampingFactor = 0.2; this.controls.rotateSpeed = 0.25; this.controls.enableZoom = true; - //this.controls.enablePan = false; // Move lights with scene this.controls.addEventListener('change', function (scope) { @@ -342,6 +365,7 @@ module.exports = { var mesh = new THREE.Mesh(geometry, material); this.update_tool(mesh); + mesh.visible = this.showTool; scene.add(mesh); return mesh; }, @@ -393,10 +417,17 @@ module.exports = { }, - draw_path: function (scene) { - var cutting = [0, 1, 0]; - var rapid = [1, 0, 0]; + get_color: function (rapid, speed) { + if (rapid) return [1, 0, 0]; + + var intensity = speed / this.toolpath.maxSpeed; + if (typeof speed == 'undefined' || !this.showIntensity) intensity = 1; + return [0, intensity, 0.5 * (1 - intensity)]; + }, + + draw_path: function (scene) { + var s = undefined; var x = this.x.pos; var y = this.y.pos; var z = this.z.pos; @@ -407,7 +438,9 @@ module.exports = { for (var i = 0; i < this.toolpath.path.length; i++) { var step = this.toolpath.path[i]; - var newColor = step.rapid ? rapid : cutting; + + s = get(step, 's', s); + var newColor = this.get_color(step.rapid, s); // Handle color change if (!i || newColor != color) { @@ -416,6 +449,7 @@ module.exports = { colors.push.apply(colors, color); } + // Draw to move target x = get(step, 'x', x); y = get(step, 'y', y); z = get(step, 'z', z); @@ -533,7 +567,7 @@ module.exports = { scene.add(this.lights); // Model - this.path = this.draw_path(scene); + this.pathView = this.draw_path(scene); this.surfaceMesh = this.draw_surface(scene, this.surfaceMaterial); this.workpieceMesh = this.draw_workpiece(scene, this.surfaceMaterial); this.update_surface_mode(this.surfaceMode); @@ -542,10 +576,10 @@ module.exports = { var bbox = this.get_model_bounds(); // Tool, axes & bounds - this.tool = this.draw_tool(scene, bbox); - this.axes = this.draw_axes(scene, bbox); - this.bbox = this.draw_bbox(scene, bbox); - this.envelope = this.draw_envelope(scene); + this.toolView = this.draw_tool(scene, bbox); + this.axesView = this.draw_axes(scene, bbox); + this.bboxView = this.draw_bbox(scene, bbox); + this.envelopeView = this.draw_envelope(scene); }, @@ -564,7 +598,7 @@ module.exports = { if (typeof o != 'undefined') bbox.union(o.geometry.boundingBox); } - add(this.path); + add(this.pathView); add(this.surfaceMesh); add(this.workpieceMesh); @@ -573,6 +607,11 @@ module.exports = { snap: function (view) { + if (view != this.snapView) { + this.snapView = view; + cookie.set('snap-view', view); + } + var bbox = this.get_model_bounds(); this.controls.reset(); bbox.getCenter(this.controls.target); diff --git a/src/js/templated-input.js b/src/js/templated-input.js index a775934..80b18fe 100644 --- a/src/js/templated-input.js +++ b/src/js/templated-input.js @@ -44,6 +44,15 @@ module.exports = { units: function () { return (this.metric || !this.template.iunit) ? this.template.unit : this.template.iunit; + }, + + + title: function () { + var s = 'Default ' + this.template.default + ' ' + + (this.template.unit || ''); + if (typeof this.template.help != 'undefined') + s = this.template.help + '\n' + s; + return s; } }, diff --git a/src/pug/templates/control-view.pug b/src/pug/templates/control-view.pug index 5d9f928..2db0d67 100644 --- a/src/pug/templates/control-view.pug +++ b/src/pug/templates/control-view.pug @@ -158,10 +158,10 @@ script#control-view-template(type="text/x-template") table.info tr - th Time - td(title="Total run time (days:hours:mins:secs)") - span(v-if="plan_time") {{plan_time | time}} of  - | {{toolpath.time | time}} + th Remaining + td(title="Total run time (days:hours:mins:secs)"). + #[span(v-if="plan_time_remaining") {{plan_time_remaining | time}} of] + {{toolpath.time | time}} tr th ETA td.eta {{eta}} diff --git a/src/pug/templates/indicators.pug b/src/pug/templates/indicators.pug index a4fd801..01974a1 100644 --- a/src/pug/templates/indicators.pug +++ b/src/pug/templates/indicators.pug @@ -170,6 +170,42 @@ script#indicators-template(type="text/x-template") th td + table.motor_fault + tr + th.header(colspan=99) + | Motor Faults + .fa(:class="motor_fault_class()", title="General motor driver fault") + + tr + th Motor + th(title="Overtemperature fault"): .fa.fa-thermometer-full + th(title="Overcurrent motor channel A") A #[.fa.fa-bolt] + th(title="Predriver fault motor channel A") + | A #[.fa.fa-exclamation-triangle] + th(title="Overcurrent motor channel B") B #[.fa.fa-bolt] + th(title="Predriver fault motor channel B") + | B #[.fa.fa-exclamation-triangle] + th(title="Driver communication failure"): .fa.fa-handshake-o + th(title="Reset all motor flags") + .fa.fa-eraser(@click="motor_reset()") + + tr(v-for="motor in [0, 1, 2, 3]") + td {{motor}} + td: .fa(:class="motor_fault_class(motor, 'temp')", + title="Overtemperature fault") + td: .fa(:class="motor_fault_class(motor, 'current a')", + title="Overcurrent motor channel A") + td: .fa(:class="motor_fault_class(motor, 'fault a')", + title="Predriver fault motor channel A") + td: .fa(:class="motor_fault_class(motor, 'current b')", + title="Overcurrent motor channel B") + td: .fa(:class="motor_fault_class(motor, 'fault b')", + title="Predriver fault motor channel B") + td: .fa(:class="motor_fault_class(motor, 'comm')", + title="Driver communication failure") + td(:title="'Reset motor ' + motor + ' flags'") + .fa.fa-eraser(@click="motor_reset(motor)") + table.measurements tr th.header(colspan=5) Measurements diff --git a/src/pug/templates/path-viewer.pug b/src/pug/templates/path-viewer.pug index 28df778..3d0d6e2 100644 --- a/src/pug/templates/path-viewer.pug +++ b/src/pug/templates/path-viewer.pug @@ -26,24 +26,28 @@ //-///////////////////////////////////////////////////////////////////////////// script#path-viewer-template(type="text/x-template") - .path-viewer(:class="{small: small, error: error}") + .path-viewer(v-show="enabled", :class="{small: small}") .path-viewer-toolbar .tool-button(title="Toggle path view size.", @click="small = !small", :class="{active: !small}") .fa.fa-arrows-alt - .tool-button(@click="showTool = !showTool", :active="showTool", + .tool-button(@click="showTool = !showTool", :class="{active: showTool}", title="Show/hide tool.") img(src="images/tool.png") - .tool-button(@click="showBBox = !showBBox", :active="showBBox", + .tool-button(@click="showBBox = !showBBox", :class="{active: showBBox}", title="Show/hide bounding box.") img(src="images/bbox.png") - .tool-button(@click="showAxes = !showAxes", :active="showAxes", + .tool-button(@click="showAxes = !showAxes", :class="{active: showAxes}", title="Show/hide axes.") img(src="images/axes.png") + .tool-button(@click="showIntensity = !showIntensity", + :class="{active: showIntensity}", title="Show/hide LASER intensity.") + img(src="images/intensity.png") + each view in "isometric top front".split(" ") .tool-button(@click=`snap('${view}')`, title=`Snap to ${view} view.`) img(src=`images/${view}.png`) @@ -54,7 +58,6 @@ script#path-viewer-template(type="text/x-template") div(v-if="progress && progress < 1") | Simulating run {{progress | non_zero_percent 0}}. . . div(v-if="!progress || progress == 1") Loading. . . - | {{message}} table.path-viewer-messages( v-if="typeof toolpath.messages != 'undefined' && " + diff --git a/src/pug/templates/templated-input.pug b/src/pug/templates/templated-input.pug index 0e456ac..f1478d2 100644 --- a/src/pug/templates/templated-input.pug +++ b/src/pug/templates/templated-input.pug @@ -26,8 +26,7 @@ //-///////////////////////////////////////////////////////////////////////////// script#templated-input-template(type="text/x-template") - .pure-control-group(class="tmpl-input-{{name}}", - title="Default {{template.default}} {{template.unit || ''}}") + .pure-control-group(class="tmpl-input-{{name}}", :title="title") label(:for="name") {{name}} select(v-if="template.type == 'enum' || template.values", v-model="view", diff --git a/src/py/bbctrl/APIHandler.py b/src/py/bbctrl/APIHandler.py index 64af779..a5f02cb 100644 --- a/src/py/bbctrl/APIHandler.py +++ b/src/py/bbctrl/APIHandler.py @@ -50,6 +50,7 @@ class APIHandler(RequestHandler): log.error(str(value)) trace = ''.join(traceback.format_exception(typ, value, tb)) + log.error(trace) log.debug(trace) diff --git a/src/py/bbctrl/Camera.py b/src/py/bbctrl/Camera.py index 24d69e1..9f7a3da 100755 --- a/src/py/bbctrl/Camera.py +++ b/src/py/bbctrl/Camera.py @@ -533,7 +533,7 @@ class Camera(object): except Exception as e: - log.warning('While loading camera') + log.warning('While loading camera: %s' % e) if not self.dev is None: self.dev.close() self.dev = None diff --git a/src/py/bbctrl/Cmd.py b/src/py/bbctrl/Cmd.py index 4700471..7c53a64 100644 --- a/src/py/bbctrl/Cmd.py +++ b/src/py/bbctrl/Cmd.py @@ -43,6 +43,7 @@ SEEK = 's' SET_AXIS = 'a' LINE = 'l' SYNC_SPEED = '%' +SPEED = 'p' INPUT = 'I' DWELL = 'd' PAUSE = 'P' @@ -115,17 +116,17 @@ def line(target, exitVel, maxAccel, maxJerk, times, speeds): cmd += str(i) + encode_float(times[i] / 60000) # to mins # Speeds - for speed in speeds: - cmd += '\n' + sync_speed(speed[0], speed[1]) + for dist, speed in speeds: + cmd += '\n' + sync_speed(dist, speed) return cmd -def speed(speed): return set_float('s', speed) +def speed(value): return SPEED + encode_float(value) -def sync_speed(time, speed): - return SYNC_SPEED + encode_float(time) + encode_float(speed) +def sync_speed(dist, speed): + return SYNC_SPEED + encode_float(dist) + encode_float(speed) def input(port, mode, timeout): diff --git a/src/py/bbctrl/Ctrl.py b/src/py/bbctrl/Ctrl.py index 47cfe85..69028ca 100644 --- a/src/py/bbctrl/Ctrl.py +++ b/src/py/bbctrl/Ctrl.py @@ -48,7 +48,6 @@ class Ctrl(object): self.lcd = bbctrl.LCD(self) self.mach = bbctrl.Mach(self) self.preplanner = bbctrl.Preplanner(self) - self.planTimer = bbctrl.PlanTimer(self) self.jog = bbctrl.Jog(self) self.pwr = bbctrl.Pwr(self) diff --git a/src/py/bbctrl/FileHandler.py b/src/py/bbctrl/FileHandler.py index 6d03fa5..d122d35 100644 --- a/src/py/bbctrl/FileHandler.py +++ b/src/py/bbctrl/FileHandler.py @@ -56,7 +56,7 @@ class FileHandler(bbctrl.APIHandler): safe_remove('upload' + filename) self.ctrl.preplanner.delete_plans(filename) - if self.ctrl.state.get('selected') == filename: + if self.ctrl.state.get('selected', '') == filename: self.ctrl.state.set('selected', '') diff --git a/src/py/bbctrl/Mach.py b/src/py/bbctrl/Mach.py index 65ce235..8d83503 100644 --- a/src/py/bbctrl/Mach.py +++ b/src/py/bbctrl/Mach.py @@ -55,6 +55,12 @@ axis_homing_procedure = ''' G90 G28.3 %(axis)s[#<_%(axis)s_home_position>] ''' +motor_fault_error = '''\ +Motor %d driver fault. A potentially damaging electrical condition was \ +detected and the motor driver was shutdown. Please power down the controller \ +and check your motor cabling. See the "Motor Faults" table on the "Indicators" \ +for more information.\ +''' def overrides(interface_class): def overrider(method): @@ -73,6 +79,7 @@ class Mach(Comm): self.ctrl = ctrl self.planner = bbctrl.Planner(ctrl) + self.unpausing = False ctrl.state.set('cycle', 'idle') self._update_cycle_cb(False) @@ -114,9 +121,19 @@ class Mach(Comm): # Handle EStop if update.get('xx', '') == 'ESTOPPED': self.planner.reset() + # Unpause sync + if update.get('xx', '') != 'HOLDING': self.unpausing = False + # Update cycle now, if it has changed self._update_cycle() + # Detect motor faults + for motor in range(4): + key = '%ddf' % motor + if key in update and update[key] & 0x1f: + log.error(motor_fault_error % motor) + + # Unpause if (('xx' in update or 'pr' in update) and self.ctrl.state.get('xx', '') == 'HOLDING'): pause_reason = self.ctrl.state.get('pr', '') @@ -135,6 +152,9 @@ class Mach(Comm): def _unpause(self): + if self._get_state() != 'HOLDING' or self.unpausing: return + self.unpausing = True + pause_reason = self.ctrl.state.get('pr', '') log.info('Unpause: ' + pause_reason) @@ -268,8 +288,10 @@ class Mach(Comm): def start(self): + filename = self.ctrl.state.get('selected', '') + if not filename: return self._begin_cycle('running') - self.planner.load('upload/' + self.ctrl.state.get('selected')) + self.planner.load('upload/' + filename) super().resume() diff --git a/src/py/bbctrl/MainLCDPage.py b/src/py/bbctrl/MainLCDPage.py index b55f921..ba17391 100644 --- a/src/py/bbctrl/MainLCDPage.py +++ b/src/py/bbctrl/MainLCDPage.py @@ -54,7 +54,11 @@ class MainLCDPage(bbctrl.LCDPage): # Show enabled axes row = 0 for axis in 'xyzabc': - if state.is_axis_enabled(axis): + if state.is_axis_faulted(axis): + self.text(' FAULT %s' % axis.upper(), 9, row) + row += 1 + + elif state.is_axis_enabled(axis): position = state.get(axis + 'p', 0) position += state.get('offset_' + axis, 0) position /= scale diff --git a/src/py/bbctrl/PlanTimer.py b/src/py/bbctrl/PlanTimer.py deleted file mode 100644 index 05b9d60..0000000 --- a/src/py/bbctrl/PlanTimer.py +++ /dev/null @@ -1,117 +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 . # -# # -# 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 # -# . # -# # -# For information regarding this software email: # -# "Joseph Coffland" # -# # -################################################################################ - -import logging -import time -import bbctrl - -log = logging.getLogger('PlanTimer') - - -class PlanTimer(object): - def __init__(self, ctrl): - self.ctrl = ctrl - self.plan_times = None - - self.reset() - self.ctrl.state.set('plan_time', 0) - ctrl.state.add_listener(self._update) - self._report() - - - def reset(self): - self.plan_time = 0 - self.move_start = None - self.hold_start = None - self.plan_index = 0 - - - def _report(self): - if (self.plan_times is not None and - self.plan_index < len(self.plan_times) and - self.move_start is not None): - state = self.ctrl.state.get('xx', '') - - if state in ['STOPPING', 'RUNNING']: - t = self.plan_time - delta = time.time() - self.move_start - nextT = self.plan_times[self.plan_index][1] - if t + delta < nextT: t += delta - else: t = nextT - - self.ctrl.state.set('plan_time', round(t)) - - self.ctrl.ioloop.call_later(1, self._report) - - - def _update_state(self, state): - if state in ['READY', 'ESTOPPED']: - self.ctrl.state.set('plan_time', 0) - self.reset() - - elif state == 'HOLDING': self.hold_start = time.time() - elif (state == 'RUNNING' and self.hold_start is not None and - self.move_start is not None): - self.move_start += time.time() - self.hold_start - self.hold_start = None - - - def _update_times(self, filename): - if not filename: return - future = self.ctrl.preplanner.get_plan(filename) - - def cb(future): - if (filename != self.ctrl.state.get('selected') or - future.cancelled()): return - - self.reset() - path, meta = future.result() - self.plan_times = meta['times'] - - self.ctrl.ioloop.add_future(future, cb) - - - def _update_time(self, currentID): - if self.plan_times is None: return - - while self.plan_index < len(self.plan_times): - id, t = self.plan_times[self.plan_index] - if id <= currentID: self.move_start = time.time() - if currentID <= id: break - self.plan_time = t - self.plan_index += 1 - - - def _update(self, update): - # Check state - if 'xx' in update: self._update_state(update['xx']) - - # Get plan times - if 'selected' in update: self._update_times(update['selected']) - - # Get plan time for current id - if 'id' in update: self._update_time(update['id']) diff --git a/src/py/bbctrl/Planner.py b/src/py/bbctrl/Planner.py index 459619f..fa69e14 100644 --- a/src/py/bbctrl/Planner.py +++ b/src/py/bbctrl/Planner.py @@ -30,6 +30,7 @@ import math import re import logging import threading +import time from collections import deque import camotics.gplan as gplan # pylint: disable=no-name-in-module,import-error import bbctrl.Cmd as Cmd @@ -55,6 +56,7 @@ class Planner(): ctrl.state.add_listener(self._update) self.reset() + self._report_time() def is_busy(self): return self.is_running() or self.cmdq.is_active() @@ -109,6 +111,7 @@ class Planner(): 'max-vel': self._get_config_vector('vm', 1000), 'max-accel': self._get_config_vector('am', 1000000), 'max-jerk': self._get_config_vector('jm', 1000000), + 'rapid-auto-off': self.ctrl.config.get('rapid-auto-off'), # TODO junction deviation & accel } @@ -128,7 +131,6 @@ class Planner(): program_start = self.ctrl.config.get('program-start') if program_start: config['program-start'] = program_start - overrides = {} tool_change = self.ctrl.config.get('tool-change') @@ -208,12 +210,56 @@ class Planner(): self.cmdq.enqueue(id, self.ctrl.state.set, name, value) + def _report_time(self): + state = self.ctrl.state.get('xx', '') + + if state in ['STOPPING', 'RUNNING'] and self.move_start: + delta = time.time() - self.move_start + if self.move_time < delta: delta = self.move_time + plan_time = self.current_plan_time + delta + + self.ctrl.state.set('plan_time', round(plan_time)) + + elif state != 'HOLDING': self.ctrl.state.set('plan_time', 0) + + self.ctrl.ioloop.call_later(1, self._report_time) + + + def _plan_time_restart(self): + self.plan_time = self.ctrl.state.get('plan_time', 0) + + + def _update_time(self, plan_time, move_time): + self.current_plan_time = plan_time + self.move_time = move_time + self.move_start = time.time() + + + def _enqueue_line_time(self, block): + if block.get('first', False) or block.get('seeking', False): return + + # Sum move times + move_time = sum(block['times']) / 1000 # To seconds + + self.cmdq.enqueue(block['id'], self._update_time, self.plan_time, + move_time) + + self.plan_time += move_time + + + def _enqueue_dwell_time(self, block): + self.cmdq.enqueue(block['id'], self._update_time, self.plan_time, + block['seconds']) + self.plan_time += block['seconds'] + + def __encode(self, block): type, id = block['type'], block['id'] if type != 'set': log.info('Cmd:' + json.dumps(block)) if type == 'line': + self._enqueue_line_time(block) return Cmd.line(block['target'], block['exit-vel'], block['max-accel'], block['max-jerk'], block['times'], block.get('speeds', [])) @@ -222,12 +268,10 @@ class Planner(): name, value = block['name'], block['value'] if name == 'message': - self.cmdq.enqueue( - id, self.ctrl.msgs.broadcast, {'message': value}) - - if name in ['line', 'tool']: - self._enqueue_set_cmd(id, name, value) + msg = dict(message = value) + self.cmdq.enqueue(id, self.ctrl.msgs.broadcast, msg) + if name in ['line', 'tool']: self._enqueue_set_cmd(id, name, value) if name == 'speed': return Cmd.speed(value) if len(name) and name[0] == '_': @@ -235,6 +279,9 @@ class Planner(): if len(name) != 2 or name[1] not in 'xyzabc': self._enqueue_set_cmd(id, name[1:], value) + if name == '_feed': # Must come after _enqueue_set_cmd() above + return Cmd.set_sync('if', 1 / value if value else 0) + if name[0:1] == '_' and name[1:2] in 'xyzabc': if name[2:] == '_home': return Cmd.set_axis(name[1], value) @@ -253,7 +300,10 @@ class Planner(): if type == 'output': return Cmd.output(block['port'], int(float(block['value']))) - if type == 'dwell': return Cmd.dwell(block['seconds']) + if type == 'dwell': + self._enqueue_dwell_time(block) + return Cmd.dwell(block['seconds']) + if type == 'pause': return Cmd.pause(block['pause-type']) if type == 'seek': return Cmd.seek(block['switch'], block['active'], block['error']) @@ -270,22 +320,32 @@ class Planner(): return Cmd.set_sync('id', block['id']) + '\n' + cmd + def reset_times(self): + self.move_start = 0 + self.move_time = 0 + self.plan_time = 0 + self.current_plan_time = 0 + + def reset(self): - if (hasattr(self.ctrl, 'mach')): self.ctrl.mach.stop() + if hasattr(self.ctrl, 'mach'): self.ctrl.mach.stop() self.planner = gplan.Planner() self.planner.set_resolver(self._get_var_cb) self.planner.set_logger(self._log_cb, 1, 'LinePlanner:3') self.cmdq.clear() + self.reset_times() def mdi(self, cmd, with_limits = True): log.info('MDI:' + cmd) self.planner.load_string(cmd, self.get_config(True, with_limits)) + self.reset_times() def load(self, path): log.info('GCode:' + path) self.planner.load(path, self.get_config(False, True)) + self.reset_times() def stop(self): @@ -310,6 +370,9 @@ class Planner(): position[axis] = state.get(axis + 'p') log.info('Planner restart: %d %s' % (id, json.dumps(position))) + self.cmdq.clear() + self.cmdq.release(id) + self._plan_time_restart() self.planner.restart(id, position) if self.planner.is_synchronizing(): diff --git a/src/py/bbctrl/Preplanner.py b/src/py/bbctrl/Preplanner.py index f506afc..764f210 100644 --- a/src/py/bbctrl/Preplanner.py +++ b/src/py/bbctrl/Preplanner.py @@ -91,21 +91,54 @@ def hash_dump(o): def plan_hash(path, config): + path = 'upload/' + path h = hashlib.sha256() + h.update('v2'.encode('utf8')) h.update(hash_dump(config)) - with open('upload/' + path, 'rb') as f: h.update(f.read()) + + with open(path, 'rb') as f: + while True: + buf = f.read(1024 * 1024) + if not buf: break + h.update(buf) + return h.hexdigest() +def compute_unit(a, b): + unit = dict() + length = 0 + + for axis in 'xyzabc': + if axis in a and axis in b: + unit[axis] = b[axis] - a[axis] + length += unit[axis] * unit[axis] + + length = math.sqrt(length) + + for axis in 'xyzabc': + if axis in unit: unit[axis] /= length + + return unit + + +def compute_move(start, unit, dist): + move = dict() + + for axis in 'xyzabc': + if axis in unit and axis in start: + move[axis] = start[axis] + unit[axis] * dist + + return move + + class Preplanner(object): - def __init__(self, ctrl, threads = 4, max_plan_time = 600, + def __init__(self, ctrl, threads = 4, max_preplan_time = 600, max_loop_time = 30): self.ctrl = ctrl - self.max_plan_time = max_plan_time + self.max_preplan_time = max_preplan_time self.max_loop_time = max_loop_time - ctrl.state.add_listener(self._update) - for dir in ['plans', 'meta']: if not os.path.exists(dir): os.mkdir(dir) @@ -115,10 +148,14 @@ class Preplanner(object): self.pool = ThreadPoolExecutor(threads) self.lock = threading.Lock() + # Must be last + ctrl.state.add_listener(self._update) + def _update(self, update): if not 'selected' in update: return filename = update['selected'] + if filename is None: return future = self.get_plan(filename) def set_bounds(type, bounds): @@ -128,7 +165,7 @@ class Preplanner(object): bounds[type][axis]) def cb(future): - if (filename != self.ctrl.state.get('selected') or + if (filename != self.ctrl.state.get('selected', '') or future.cancelled()): return path, meta = future.result() @@ -156,7 +193,10 @@ class Preplanner(object): def delete_all_plans(self): - for path in glob.glob('plans/*'): + files = glob.glob('plans/*') + files += glob.glob('meta/*') + + for path in files: try: os.unlink(path) except OSError: pass @@ -165,7 +205,10 @@ class Preplanner(object): def delete_plans(self, filename): - for path in glob.glob('plans/' + filename + '.*'): + files = glob.glob('plans/' + filename + '.*') + files += glob.glob('meta/' + filename + '.*') + + for path in files: try: os.unlink(path) except OSError: pass @@ -174,6 +217,8 @@ class Preplanner(object): def get_plan(self, filename): + if filename is None: raise Exception('Filename cannot be None') + with self.lock: if filename in self.plans: plan = self.plans[filename] else: @@ -263,14 +308,16 @@ class Preplanner(object): maxLineTime = time.time() totalTime = 0 position = {} + maxSpeed = 0 + currentSpeed = None rapid = False moves = [] - times = [] bounds = dict(min = {}, max = {}) messages = [] count = 0 cancelled = False + # Initialized axis states and bounds for axis in 'xyzabc': position[axis] = 0 bounds['min'][axis] = math.inf @@ -281,20 +328,37 @@ class Preplanner(object): if bounds['max'][axis] < value: bounds['max'][axis] = value + def update_speed(s): + nonlocal currentSpeed, maxSpeed + if currentSpeed == s: return False + currentSpeed = s + if maxSpeed < s: maxSpeed = s + return True + + + # Capture planner log messages levels = dict(I = 'info', D = 'debug', W = 'warning', E = 'error', C = 'critical') def log_cb(level, msg, filename, line, column): if level in levels: level = levels[level] + + # Ignore missing tool warning + if (level == 'warning' and + msg.startswith('Auto-creating missing tool')): + return + messages.append(dict(level = level, msg = msg, filename = filename, line = line, column = column)) + # Initialize planner self.ctrl.mach.planner.log_intercept(log_cb) planner = gplan.Planner() planner.set_resolver(get_var_cb) planner.load('upload/' + filename, config) + # Execute plan try: while planner.has_more(): cmd = planner.next() @@ -304,40 +368,57 @@ class Preplanner(object): if planner.is_synchronizing(): planner.synchronize(0) if cmd['type'] == 'line': - if 'first' in cmd: continue + if not (cmd.get('first', False) or + cmd.get('seeking', False)): + totalTime += sum(cmd['times']) / 1000 - totalTime += sum(cmd['times']) / 1000 - times.append((cmd['id'], totalTime)) target = cmd['target'] move = {} + startPos = dict() for axis in 'xyzabc': if axis in target: + startPos[axis] = position[axis] position[axis] = target[axis] move[axis] = target[axis] add_to_bounds(axis, move[axis]) if 'rapid' in cmd: move['rapid'] = cmd['rapid'] + if 'speeds' in cmd: + unit = compute_unit(startPos, target) + + for d, s in cmd['speeds']: + cur = currentSpeed + + if update_speed(s): + m = compute_move(startPos, unit, d) + m['s'] = cur + moves.append(m) + move['s'] = s + moves.append(move) - elif cmd['type'] == 'set' and cmd['name'] == 'line': - line = cmd['value'] - if maxLine < line: - maxLine = line - maxLineTime = time.time() + elif cmd['type'] == 'set': + if cmd['name'] == 'line': + line = cmd['value'] + if maxLine < line: + maxLine = line + maxLineTime = time.time() + + elif cmd['name'] == 'speed': + s = cmd['value'] + if update_speed(s): moves.append({'s': s}) - elif cmd['type'] == 'dwell': - totalTime += cmd['seconds'] - times.append((cmd['id'], totalTime)) + elif cmd['type'] == 'dwell': totalTime += cmd['seconds'] if not self._progress(filename, maxLine / totalLines): cancelled = True raise Exception('Plan canceled.') - if self.max_plan_time < time.time() - start: + if self.max_preplan_time < time.time() - start: raise Exception('Max planning time (%d sec) exceeded.' % - self.max_plan_time) + self.max_preplan_time) if self.max_loop_time < time.time() - maxLineTime: raise Exception('Max loop time (%d sec) exceeded.' % @@ -358,11 +439,11 @@ class Preplanner(object): # Encode data as string data = dict(time = totalTime, lines = totalLines, path = moves, - messages = messages) + maxSpeed = maxSpeed, messages = messages) data = gzip.compress(dump_json(data).encode('utf8')) # Meta data - meta = dict(times = times, bounds = bounds) + meta = dict(bounds = bounds) meta_comp = gzip.compress(dump_json(meta).encode('utf8')) # Save plan & meta data diff --git a/src/py/bbctrl/State.py b/src/py/bbctrl/State.py index 6d8a3a5..938f76f 100644 --- a/src/py/bbctrl/State.py +++ b/src/py/bbctrl/State.py @@ -233,6 +233,15 @@ class State(object): return axes + def is_motor_faulted(self, motor): + return self.get('%ddf' % motor, 0) & 0x1f + + + def is_axis_faulted(self, axis): + motor = self.find_motor(axis) + return motor is not None and self.is_motor_faulted(motor) + + def axis_homing_mode(self, axis): motor = self.find_motor(axis) if motor is None: return 'disabled' diff --git a/src/py/bbctrl/Web.py b/src/py/bbctrl/Web.py index 9b7c8b5..1062b9c 100644 --- a/src/py/bbctrl/Web.py +++ b/src/py/bbctrl/Web.py @@ -249,16 +249,19 @@ class PathHandler(bbctrl.APIHandler): self.write_json(dict(progress = progress)) return - if data is not None: - data = data[0] # We only want the compressed path - self.set_header('Content-Encoding', 'gzip') - - # Respond with chunks to avoid long delays - SIZE = 102400 - chunks = [data[i:i + SIZE] for i in range(0, len(data), SIZE)] - for chunk in chunks: - self.write(chunk) - yield self.flush() + try: + if data is not None: + data = data[0] # We only want the compressed path + self.set_header('Content-Encoding', 'gzip') + + # Respond with chunks to avoid long delays + SIZE = 102400 + chunks = [data[i:i + SIZE] for i in range(0, len(data), SIZE)] + for chunk in chunks: + self.write(chunk) + yield self.flush() + + except tornado.iostream.StreamClosedError as e: pass class HomeHandler(bbctrl.APIHandler): diff --git a/src/py/bbctrl/__init__.py b/src/py/bbctrl/__init__.py index d18c7fa..b169d97 100644 --- a/src/py/bbctrl/__init__.py +++ b/src/py/bbctrl/__init__.py @@ -57,7 +57,6 @@ from bbctrl.CommandQueue import CommandQueue from bbctrl.MainLCDPage import MainLCDPage from bbctrl.IPLCDPage import IPLCDPage from bbctrl.Camera import Camera, VideoHandler -from bbctrl.PlanTimer import PlanTimer import bbctrl.Cmd as Cmd import bbctrl.v4l2 as v4l2 diff --git a/src/py/bbctrl/v4l2.py b/src/py/bbctrl/v4l2.py index 5d8ca83..02c49b3 100644 --- a/src/py/bbctrl/v4l2.py +++ b/src/py/bbctrl/v4l2.py @@ -1016,11 +1016,18 @@ class v4l2_ext_controls(ctypes.Structure): ] -V4L2_CTRL_CLASS_USER = 0x00980000 -V4L2_CTRL_CLASS_MPEG = 0x00990000 -V4L2_CTRL_CLASS_CAMERA = 0x009a0000 -V4L2_CTRL_CLASS_FM_TX = 0x009b0000 - +V4L2_CTRL_CLASS_USER = 0x00980000 # Old-style 'user' controls +V4L2_CTRL_CLASS_MPEG = 0x00990000 # MPEG-compression controls +V4L2_CTRL_CLASS_CAMERA = 0x009a0000 # Camera class controls +V4L2_CTRL_CLASS_FM_TX = 0x009b0000 # FM Modulator controls +V4L2_CTRL_CLASS_FLASH = 0x009c0000 # Camera flash controls +V4L2_CTRL_CLASS_JPEG = 0x009d0000 # JPEG-compression controls +V4L2_CTRL_CLASS_IMAGE_SOURCE = 0x009e0000 # Image source controls +V4L2_CTRL_CLASS_IMAGE_PROC = 0x009f0000 # Image processing controls +V4L2_CTRL_CLASS_DV = 0x00a00000 # Digital Video controls +V4L2_CTRL_CLASS_FM_RX = 0x00a10000 # FM Receiver controls +V4L2_CTRL_CLASS_RF_TUNER = 0x00a20000 # RF tuner controls +V4L2_CTRL_CLASS_DETECT = 0x00a30000 # Detection controls def V4L2_CTRL_ID_MASK(): return 0x0fffffff @@ -1466,6 +1473,34 @@ V4L2_CID_TUNE_POWER_LEVEL = V4L2_CID_FM_TX_CLASS_BASE + 113 V4L2_CID_TUNE_ANTENNA_CAPACITOR = V4L2_CID_FM_TX_CLASS_BASE + 114 +# JPEG-class control IDs + +V4L2_CID_JPEG_CLASS_BASE = V4L2_CTRL_CLASS_JPEG | 0x900 +V4L2_CID_JPEG_CLASS = V4L2_CTRL_CLASS_JPEG | 1 + +V4L2_CID_JPEG_CHROMA_SUBSAMPLING = V4L2_CID_JPEG_CLASS_BASE + 1 + +v4l2_jpeg_chroma_subsampling = enum +( + V4L2_JPEG_CHROMA_SUBSAMPLING_444, + V4L2_JPEG_CHROMA_SUBSAMPLING_422, + V4L2_JPEG_CHROMA_SUBSAMPLING_420, + V4L2_JPEG_CHROMA_SUBSAMPLING_411, + V4L2_JPEG_CHROMA_SUBSAMPLING_410, + V4L2_JPEG_CHROMA_SUBSAMPLING_GRAY, +) = range(6) + +V4L2_CID_JPEG_RESTART_INTERVAL = V4L2_CID_JPEG_CLASS_BASE + 2 +V4L2_CID_JPEG_COMPRESSION_QUALITY = V4L2_CID_JPEG_CLASS_BASE + 3 + +V4L2_CID_JPEG_ACTIVE_MARKER = V4L2_CID_JPEG_CLASS_BASE + 4 +V4L2_JPEG_ACTIVE_MARKER_APP0 = 1 << 0 +V4L2_JPEG_ACTIVE_MARKER_APP1 = 1 << 1 +V4L2_JPEG_ACTIVE_MARKER_COM = 1 << 16 +V4L2_JPEG_ACTIVE_MARKER_DQT = 1 << 17 +V4L2_JPEG_ACTIVE_MARKER_DHT = 1 << 18 + + # # Tuning # diff --git a/src/resources/config-template.json b/src/resources/config-template.json index 7aa38be..a9a275b 100644 --- a/src/resources/config-template.json +++ b/src/resources/config-template.json @@ -292,6 +292,7 @@ "pwm-spindle": { "pwm-inverted": { + "help": "Invert the PWM signal output.", "type": "bool", "default": false, "code": "pi" @@ -319,6 +320,18 @@ "max": 320000, "default": 1000, "code": "sf" + }, + "rapid-auto-off": { + "help": "Turn tool off during rapid moves. Useful for LASERs.", + "type": "bool", + "default": false + }, + "dynamic-power": { + "help": + "Adjust tool power based on velocity and feed rate. Useful for LASERs.", + "type": "bool", + "default": false, + "code": "dp" } }, diff --git a/src/resources/fonts/fontawesome-webfont.ttf b/src/resources/fonts/fontawesome-webfont.ttf index 26dea79..35acda2 100644 Binary files a/src/resources/fonts/fontawesome-webfont.ttf and b/src/resources/fonts/fontawesome-webfont.ttf differ diff --git a/src/resources/fonts/fontawesome-webfont.woff b/src/resources/fonts/fontawesome-webfont.woff index dc35ce3..400014a 100644 Binary files a/src/resources/fonts/fontawesome-webfont.woff and b/src/resources/fonts/fontawesome-webfont.woff differ diff --git a/src/resources/fonts/fontawesome-webfont.woff2 b/src/resources/fonts/fontawesome-webfont.woff2 index 500e517..4d13fc6 100644 Binary files a/src/resources/fonts/fontawesome-webfont.woff2 and b/src/resources/fonts/fontawesome-webfont.woff2 differ diff --git a/src/resources/images/intensity.png b/src/resources/images/intensity.png new file mode 100644 index 0000000..be9972d Binary files /dev/null and b/src/resources/images/intensity.png differ diff --git a/src/static/css/font-awesome.min.css b/src/static/css/font-awesome.min.css index d0603cb..540440c 100644 --- a/src/static/css/font-awesome.min.css +++ b/src/static/css/font-awesome.min.css @@ -1,4 +1,4 @@ /*! - * Font Awesome 4.5.0 by @davegandy - http://fontawesome.io - @fontawesome + * Font Awesome 4.7.0 by @davegandy - http://fontawesome.io - @fontawesome * License - http://fontawesome.io/license (Font: SIL OFL 1.1, CSS: MIT License) - */@font-face{font-family:'FontAwesome';src:url('../fonts/fontawesome-webfont.eot?v=4.5.0');src:url('../fonts/fontawesome-webfont.eot?#iefix&v=4.5.0') format('embedded-opentype'),url('../fonts/fontawesome-webfont.woff2?v=4.5.0') format('woff2'),url('../fonts/fontawesome-webfont.woff?v=4.5.0') format('woff'),url('../fonts/fontawesome-webfont.ttf?v=4.5.0') format('truetype'),url('../fonts/fontawesome-webfont.svg?v=4.5.0#fontawesomeregular') format('svg');font-weight:normal;font-style:normal}.fa{display:inline-block;font:normal normal normal 14px/1 FontAwesome;font-size:inherit;text-rendering:auto;-webkit-font-smoothing:antialiased;-moz-osx-font-smoothing:grayscale}.fa-lg{font-size:1.33333333em;line-height:.75em;vertical-align:-15%}.fa-2x{font-size:2em}.fa-3x{font-size:3em}.fa-4x{font-size:4em}.fa-5x{font-size:5em}.fa-fw{width:1.28571429em;text-align:center}.fa-ul{padding-left:0;margin-left:2.14285714em;list-style-type:none}.fa-ul>li{position:relative}.fa-li{position:absolute;left:-2.14285714em;width:2.14285714em;top:.14285714em;text-align:center}.fa-li.fa-lg{left:-1.85714286em}.fa-border{padding:.2em .25em .15em;border:solid .08em #eee;border-radius:.1em}.fa-pull-left{float:left}.fa-pull-right{float:right}.fa.fa-pull-left{margin-right:.3em}.fa.fa-pull-right{margin-left:.3em}.pull-right{float:right}.pull-left{float:left}.fa.pull-left{margin-right:.3em}.fa.pull-right{margin-left:.3em}.fa-spin{-webkit-animation:fa-spin 2s infinite linear;animation:fa-spin 2s infinite linear}.fa-pulse{-webkit-animation:fa-spin 1s infinite steps(8);animation:fa-spin 1s infinite steps(8)}@-webkit-keyframes fa-spin{0%{-webkit-transform:rotate(0deg);transform:rotate(0deg)}100%{-webkit-transform:rotate(359deg);transform:rotate(359deg)}}@keyframes fa-spin{0%{-webkit-transform:rotate(0deg);transform:rotate(0deg)}100%{-webkit-transform:rotate(359deg);transform:rotate(359deg)}}.fa-rotate-90{filter:progid:DXImageTransform.Microsoft.BasicImage(rotation=1);-webkit-transform:rotate(90deg);-ms-transform:rotate(90deg);transform:rotate(90deg)}.fa-rotate-180{filter:progid:DXImageTransform.Microsoft.BasicImage(rotation=2);-webkit-transform:rotate(180deg);-ms-transform:rotate(180deg);transform:rotate(180deg)}.fa-rotate-270{filter:progid:DXImageTransform.Microsoft.BasicImage(rotation=3);-webkit-transform:rotate(270deg);-ms-transform:rotate(270deg);transform:rotate(270deg)}.fa-flip-horizontal{filter:progid:DXImageTransform.Microsoft.BasicImage(rotation=0, mirror=1);-webkit-transform:scale(-1, 1);-ms-transform:scale(-1, 1);transform:scale(-1, 1)}.fa-flip-vertical{filter:progid:DXImageTransform.Microsoft.BasicImage(rotation=2, mirror=1);-webkit-transform:scale(1, -1);-ms-transform:scale(1, -1);transform:scale(1, -1)}:root .fa-rotate-90,:root .fa-rotate-180,:root .fa-rotate-270,:root .fa-flip-horizontal,:root .fa-flip-vertical{filter:none}.fa-stack{position:relative;display:inline-block;width:2em;height:2em;line-height:2em;vertical-align:middle}.fa-stack-1x,.fa-stack-2x{position:absolute;left:0;width:100%;text-align:center}.fa-stack-1x{line-height:inherit}.fa-stack-2x{font-size:2em}.fa-inverse{color:#fff}.fa-glass:before{content:"\f000"}.fa-music:before{content:"\f001"}.fa-search:before{content:"\f002"}.fa-envelope-o:before{content:"\f003"}.fa-heart:before{content:"\f004"}.fa-star:before{content:"\f005"}.fa-star-o:before{content:"\f006"}.fa-user:before{content:"\f007"}.fa-film:before{content:"\f008"}.fa-th-large:before{content:"\f009"}.fa-th:before{content:"\f00a"}.fa-th-list:before{content:"\f00b"}.fa-check:before{content:"\f00c"}.fa-remove:before,.fa-close:before,.fa-times:before{content:"\f00d"}.fa-search-plus:before{content:"\f00e"}.fa-search-minus:before{content:"\f010"}.fa-power-off:before{content:"\f011"}.fa-signal:before{content:"\f012"}.fa-gear:before,.fa-cog:before{content:"\f013"}.fa-trash-o:before{content:"\f014"}.fa-home:before{content:"\f015"}.fa-file-o:before{content:"\f016"}.fa-clock-o:before{content:"\f017"}.fa-road:before{content:"\f018"}.fa-download:before{content:"\f019"}.fa-arrow-circle-o-down:before{content:"\f01a"}.fa-arrow-circle-o-up:before{content:"\f01b"}.fa-inbox:before{content:"\f01c"}.fa-play-circle-o:before{content:"\f01d"}.fa-rotate-right:before,.fa-repeat:before{content:"\f01e"}.fa-refresh:before{content:"\f021"}.fa-list-alt:before{content:"\f022"}.fa-lock:before{content:"\f023"}.fa-flag:before{content:"\f024"}.fa-headphones:before{content:"\f025"}.fa-volume-off:before{content:"\f026"}.fa-volume-down:before{content:"\f027"}.fa-volume-up:before{content:"\f028"}.fa-qrcode:before{content:"\f029"}.fa-barcode:before{content:"\f02a"}.fa-tag:before{content:"\f02b"}.fa-tags:before{content:"\f02c"}.fa-book:before{content:"\f02d"}.fa-bookmark:before{content:"\f02e"}.fa-print:before{content:"\f02f"}.fa-camera:before{content:"\f030"}.fa-font:before{content:"\f031"}.fa-bold:before{content:"\f032"}.fa-italic:before{content:"\f033"}.fa-text-height:before{content:"\f034"}.fa-text-width:before{content:"\f035"}.fa-align-left:before{content:"\f036"}.fa-align-center:before{content:"\f037"}.fa-align-right:before{content:"\f038"}.fa-align-justify:before{content:"\f039"}.fa-list:before{content:"\f03a"}.fa-dedent:before,.fa-outdent:before{content:"\f03b"}.fa-indent:before{content:"\f03c"}.fa-video-camera:before{content:"\f03d"}.fa-photo:before,.fa-image:before,.fa-picture-o:before{content:"\f03e"}.fa-pencil:before{content:"\f040"}.fa-map-marker:before{content:"\f041"}.fa-adjust:before{content:"\f042"}.fa-tint:before{content:"\f043"}.fa-edit:before,.fa-pencil-square-o:before{content:"\f044"}.fa-share-square-o:before{content:"\f045"}.fa-check-square-o:before{content:"\f046"}.fa-arrows:before{content:"\f047"}.fa-step-backward:before{content:"\f048"}.fa-fast-backward:before{content:"\f049"}.fa-backward:before{content:"\f04a"}.fa-play:before{content:"\f04b"}.fa-pause:before{content:"\f04c"}.fa-stop:before{content:"\f04d"}.fa-forward:before{content:"\f04e"}.fa-fast-forward:before{content:"\f050"}.fa-step-forward:before{content:"\f051"}.fa-eject:before{content:"\f052"}.fa-chevron-left:before{content:"\f053"}.fa-chevron-right:before{content:"\f054"}.fa-plus-circle:before{content:"\f055"}.fa-minus-circle:before{content:"\f056"}.fa-times-circle:before{content:"\f057"}.fa-check-circle:before{content:"\f058"}.fa-question-circle:before{content:"\f059"}.fa-info-circle:before{content:"\f05a"}.fa-crosshairs:before{content:"\f05b"}.fa-times-circle-o:before{content:"\f05c"}.fa-check-circle-o:before{content:"\f05d"}.fa-ban:before{content:"\f05e"}.fa-arrow-left:before{content:"\f060"}.fa-arrow-right:before{content:"\f061"}.fa-arrow-up:before{content:"\f062"}.fa-arrow-down:before{content:"\f063"}.fa-mail-forward:before,.fa-share:before{content:"\f064"}.fa-expand:before{content:"\f065"}.fa-compress:before{content:"\f066"}.fa-plus:before{content:"\f067"}.fa-minus:before{content:"\f068"}.fa-asterisk:before{content:"\f069"}.fa-exclamation-circle:before{content:"\f06a"}.fa-gift:before{content:"\f06b"}.fa-leaf:before{content:"\f06c"}.fa-fire:before{content:"\f06d"}.fa-eye:before{content:"\f06e"}.fa-eye-slash:before{content:"\f070"}.fa-warning:before,.fa-exclamation-triangle:before{content:"\f071"}.fa-plane:before{content:"\f072"}.fa-calendar:before{content:"\f073"}.fa-random:before{content:"\f074"}.fa-comment:before{content:"\f075"}.fa-magnet:before{content:"\f076"}.fa-chevron-up:before{content:"\f077"}.fa-chevron-down:before{content:"\f078"}.fa-retweet:before{content:"\f079"}.fa-shopping-cart:before{content:"\f07a"}.fa-folder:before{content:"\f07b"}.fa-folder-open:before{content:"\f07c"}.fa-arrows-v:before{content:"\f07d"}.fa-arrows-h:before{content:"\f07e"}.fa-bar-chart-o:before,.fa-bar-chart:before{content:"\f080"}.fa-twitter-square:before{content:"\f081"}.fa-facebook-square:before{content:"\f082"}.fa-camera-retro:before{content:"\f083"}.fa-key:before{content:"\f084"}.fa-gears:before,.fa-cogs:before{content:"\f085"}.fa-comments:before{content:"\f086"}.fa-thumbs-o-up:before{content:"\f087"}.fa-thumbs-o-down:before{content:"\f088"}.fa-star-half:before{content:"\f089"}.fa-heart-o:before{content:"\f08a"}.fa-sign-out:before{content:"\f08b"}.fa-linkedin-square:before{content:"\f08c"}.fa-thumb-tack:before{content:"\f08d"}.fa-external-link:before{content:"\f08e"}.fa-sign-in:before{content:"\f090"}.fa-trophy:before{content:"\f091"}.fa-github-square:before{content:"\f092"}.fa-upload:before{content:"\f093"}.fa-lemon-o:before{content:"\f094"}.fa-phone:before{content:"\f095"}.fa-square-o:before{content:"\f096"}.fa-bookmark-o:before{content:"\f097"}.fa-phone-square:before{content:"\f098"}.fa-twitter:before{content:"\f099"}.fa-facebook-f:before,.fa-facebook:before{content:"\f09a"}.fa-github:before{content:"\f09b"}.fa-unlock:before{content:"\f09c"}.fa-credit-card:before{content:"\f09d"}.fa-feed:before,.fa-rss:before{content:"\f09e"}.fa-hdd-o:before{content:"\f0a0"}.fa-bullhorn:before{content:"\f0a1"}.fa-bell:before{content:"\f0f3"}.fa-certificate:before{content:"\f0a3"}.fa-hand-o-right:before{content:"\f0a4"}.fa-hand-o-left:before{content:"\f0a5"}.fa-hand-o-up:before{content:"\f0a6"}.fa-hand-o-down:before{content:"\f0a7"}.fa-arrow-circle-left:before{content:"\f0a8"}.fa-arrow-circle-right:before{content:"\f0a9"}.fa-arrow-circle-up:before{content:"\f0aa"}.fa-arrow-circle-down:before{content:"\f0ab"}.fa-globe:before{content:"\f0ac"}.fa-wrench:before{content:"\f0ad"}.fa-tasks:before{content:"\f0ae"}.fa-filter:before{content:"\f0b0"}.fa-briefcase:before{content:"\f0b1"}.fa-arrows-alt:before{content:"\f0b2"}.fa-group:before,.fa-users:before{content:"\f0c0"}.fa-chain:before,.fa-link:before{content:"\f0c1"}.fa-cloud:before{content:"\f0c2"}.fa-flask:before{content:"\f0c3"}.fa-cut:before,.fa-scissors:before{content:"\f0c4"}.fa-copy:before,.fa-files-o:before{content:"\f0c5"}.fa-paperclip:before{content:"\f0c6"}.fa-save:before,.fa-floppy-o:before{content:"\f0c7"}.fa-square:before{content:"\f0c8"}.fa-navicon:before,.fa-reorder:before,.fa-bars:before{content:"\f0c9"}.fa-list-ul:before{content:"\f0ca"}.fa-list-ol:before{content:"\f0cb"}.fa-strikethrough:before{content:"\f0cc"}.fa-underline:before{content:"\f0cd"}.fa-table:before{content:"\f0ce"}.fa-magic:before{content:"\f0d0"}.fa-truck:before{content:"\f0d1"}.fa-pinterest:before{content:"\f0d2"}.fa-pinterest-square:before{content:"\f0d3"}.fa-google-plus-square:before{content:"\f0d4"}.fa-google-plus:before{content:"\f0d5"}.fa-money:before{content:"\f0d6"}.fa-caret-down:before{content:"\f0d7"}.fa-caret-up:before{content:"\f0d8"}.fa-caret-left:before{content:"\f0d9"}.fa-caret-right:before{content:"\f0da"}.fa-columns:before{content:"\f0db"}.fa-unsorted:before,.fa-sort:before{content:"\f0dc"}.fa-sort-down:before,.fa-sort-desc:before{content:"\f0dd"}.fa-sort-up:before,.fa-sort-asc:before{content:"\f0de"}.fa-envelope:before{content:"\f0e0"}.fa-linkedin:before{content:"\f0e1"}.fa-rotate-left:before,.fa-undo:before{content:"\f0e2"}.fa-legal:before,.fa-gavel:before{content:"\f0e3"}.fa-dashboard:before,.fa-tachometer:before{content:"\f0e4"}.fa-comment-o:before{content:"\f0e5"}.fa-comments-o:before{content:"\f0e6"}.fa-flash:before,.fa-bolt:before{content:"\f0e7"}.fa-sitemap:before{content:"\f0e8"}.fa-umbrella:before{content:"\f0e9"}.fa-paste:before,.fa-clipboard:before{content:"\f0ea"}.fa-lightbulb-o:before{content:"\f0eb"}.fa-exchange:before{content:"\f0ec"}.fa-cloud-download:before{content:"\f0ed"}.fa-cloud-upload:before{content:"\f0ee"}.fa-user-md:before{content:"\f0f0"}.fa-stethoscope:before{content:"\f0f1"}.fa-suitcase:before{content:"\f0f2"}.fa-bell-o:before{content:"\f0a2"}.fa-coffee:before{content:"\f0f4"}.fa-cutlery:before{content:"\f0f5"}.fa-file-text-o:before{content:"\f0f6"}.fa-building-o:before{content:"\f0f7"}.fa-hospital-o:before{content:"\f0f8"}.fa-ambulance:before{content:"\f0f9"}.fa-medkit:before{content:"\f0fa"}.fa-fighter-jet:before{content:"\f0fb"}.fa-beer:before{content:"\f0fc"}.fa-h-square:before{content:"\f0fd"}.fa-plus-square:before{content:"\f0fe"}.fa-angle-double-left:before{content:"\f100"}.fa-angle-double-right:before{content:"\f101"}.fa-angle-double-up:before{content:"\f102"}.fa-angle-double-down:before{content:"\f103"}.fa-angle-left:before{content:"\f104"}.fa-angle-right:before{content:"\f105"}.fa-angle-up:before{content:"\f106"}.fa-angle-down:before{content:"\f107"}.fa-desktop:before{content:"\f108"}.fa-laptop:before{content:"\f109"}.fa-tablet:before{content:"\f10a"}.fa-mobile-phone:before,.fa-mobile:before{content:"\f10b"}.fa-circle-o:before{content:"\f10c"}.fa-quote-left:before{content:"\f10d"}.fa-quote-right:before{content:"\f10e"}.fa-spinner:before{content:"\f110"}.fa-circle:before{content:"\f111"}.fa-mail-reply:before,.fa-reply:before{content:"\f112"}.fa-github-alt:before{content:"\f113"}.fa-folder-o:before{content:"\f114"}.fa-folder-open-o:before{content:"\f115"}.fa-smile-o:before{content:"\f118"}.fa-frown-o:before{content:"\f119"}.fa-meh-o:before{content:"\f11a"}.fa-gamepad:before{content:"\f11b"}.fa-keyboard-o:before{content:"\f11c"}.fa-flag-o:before{content:"\f11d"}.fa-flag-checkered:before{content:"\f11e"}.fa-terminal:before{content:"\f120"}.fa-code:before{content:"\f121"}.fa-mail-reply-all:before,.fa-reply-all:before{content:"\f122"}.fa-star-half-empty:before,.fa-star-half-full:before,.fa-star-half-o:before{content:"\f123"}.fa-location-arrow:before{content:"\f124"}.fa-crop:before{content:"\f125"}.fa-code-fork:before{content:"\f126"}.fa-unlink:before,.fa-chain-broken:before{content:"\f127"}.fa-question:before{content:"\f128"}.fa-info:before{content:"\f129"}.fa-exclamation:before{content:"\f12a"}.fa-superscript:before{content:"\f12b"}.fa-subscript:before{content:"\f12c"}.fa-eraser:before{content:"\f12d"}.fa-puzzle-piece:before{content:"\f12e"}.fa-microphone:before{content:"\f130"}.fa-microphone-slash:before{content:"\f131"}.fa-shield:before{content:"\f132"}.fa-calendar-o:before{content:"\f133"}.fa-fire-extinguisher:before{content:"\f134"}.fa-rocket:before{content:"\f135"}.fa-maxcdn:before{content:"\f136"}.fa-chevron-circle-left:before{content:"\f137"}.fa-chevron-circle-right:before{content:"\f138"}.fa-chevron-circle-up:before{content:"\f139"}.fa-chevron-circle-down:before{content:"\f13a"}.fa-html5:before{content:"\f13b"}.fa-css3:before{content:"\f13c"}.fa-anchor:before{content:"\f13d"}.fa-unlock-alt:before{content:"\f13e"}.fa-bullseye:before{content:"\f140"}.fa-ellipsis-h:before{content:"\f141"}.fa-ellipsis-v:before{content:"\f142"}.fa-rss-square:before{content:"\f143"}.fa-play-circle:before{content:"\f144"}.fa-ticket:before{content:"\f145"}.fa-minus-square:before{content:"\f146"}.fa-minus-square-o:before{content:"\f147"}.fa-level-up:before{content:"\f148"}.fa-level-down:before{content:"\f149"}.fa-check-square:before{content:"\f14a"}.fa-pencil-square:before{content:"\f14b"}.fa-external-link-square:before{content:"\f14c"}.fa-share-square:before{content:"\f14d"}.fa-compass:before{content:"\f14e"}.fa-toggle-down:before,.fa-caret-square-o-down:before{content:"\f150"}.fa-toggle-up:before,.fa-caret-square-o-up:before{content:"\f151"}.fa-toggle-right:before,.fa-caret-square-o-right:before{content:"\f152"}.fa-euro:before,.fa-eur:before{content:"\f153"}.fa-gbp:before{content:"\f154"}.fa-dollar:before,.fa-usd:before{content:"\f155"}.fa-rupee:before,.fa-inr:before{content:"\f156"}.fa-cny:before,.fa-rmb:before,.fa-yen:before,.fa-jpy:before{content:"\f157"}.fa-ruble:before,.fa-rouble:before,.fa-rub:before{content:"\f158"}.fa-won:before,.fa-krw:before{content:"\f159"}.fa-bitcoin:before,.fa-btc:before{content:"\f15a"}.fa-file:before{content:"\f15b"}.fa-file-text:before{content:"\f15c"}.fa-sort-alpha-asc:before{content:"\f15d"}.fa-sort-alpha-desc:before{content:"\f15e"}.fa-sort-amount-asc:before{content:"\f160"}.fa-sort-amount-desc:before{content:"\f161"}.fa-sort-numeric-asc:before{content:"\f162"}.fa-sort-numeric-desc:before{content:"\f163"}.fa-thumbs-up:before{content:"\f164"}.fa-thumbs-down:before{content:"\f165"}.fa-youtube-square:before{content:"\f166"}.fa-youtube:before{content:"\f167"}.fa-xing:before{content:"\f168"}.fa-xing-square:before{content:"\f169"}.fa-youtube-play:before{content:"\f16a"}.fa-dropbox:before{content:"\f16b"}.fa-stack-overflow:before{content:"\f16c"}.fa-instagram:before{content:"\f16d"}.fa-flickr:before{content:"\f16e"}.fa-adn:before{content:"\f170"}.fa-bitbucket:before{content:"\f171"}.fa-bitbucket-square:before{content:"\f172"}.fa-tumblr:before{content:"\f173"}.fa-tumblr-square:before{content:"\f174"}.fa-long-arrow-down:before{content:"\f175"}.fa-long-arrow-up:before{content:"\f176"}.fa-long-arrow-left:before{content:"\f177"}.fa-long-arrow-right:before{content:"\f178"}.fa-apple:before{content:"\f179"}.fa-windows:before{content:"\f17a"}.fa-android:before{content:"\f17b"}.fa-linux:before{content:"\f17c"}.fa-dribbble:before{content:"\f17d"}.fa-skype:before{content:"\f17e"}.fa-foursquare:before{content:"\f180"}.fa-trello:before{content:"\f181"}.fa-female:before{content:"\f182"}.fa-male:before{content:"\f183"}.fa-gittip:before,.fa-gratipay:before{content:"\f184"}.fa-sun-o:before{content:"\f185"}.fa-moon-o:before{content:"\f186"}.fa-archive:before{content:"\f187"}.fa-bug:before{content:"\f188"}.fa-vk:before{content:"\f189"}.fa-weibo:before{content:"\f18a"}.fa-renren:before{content:"\f18b"}.fa-pagelines:before{content:"\f18c"}.fa-stack-exchange:before{content:"\f18d"}.fa-arrow-circle-o-right:before{content:"\f18e"}.fa-arrow-circle-o-left:before{content:"\f190"}.fa-toggle-left:before,.fa-caret-square-o-left:before{content:"\f191"}.fa-dot-circle-o:before{content:"\f192"}.fa-wheelchair:before{content:"\f193"}.fa-vimeo-square:before{content:"\f194"}.fa-turkish-lira:before,.fa-try:before{content:"\f195"}.fa-plus-square-o:before{content:"\f196"}.fa-space-shuttle:before{content:"\f197"}.fa-slack:before{content:"\f198"}.fa-envelope-square:before{content:"\f199"}.fa-wordpress:before{content:"\f19a"}.fa-openid:before{content:"\f19b"}.fa-institution:before,.fa-bank:before,.fa-university:before{content:"\f19c"}.fa-mortar-board:before,.fa-graduation-cap:before{content:"\f19d"}.fa-yahoo:before{content:"\f19e"}.fa-google:before{content:"\f1a0"}.fa-reddit:before{content:"\f1a1"}.fa-reddit-square:before{content:"\f1a2"}.fa-stumbleupon-circle:before{content:"\f1a3"}.fa-stumbleupon:before{content:"\f1a4"}.fa-delicious:before{content:"\f1a5"}.fa-digg:before{content:"\f1a6"}.fa-pied-piper:before{content:"\f1a7"}.fa-pied-piper-alt:before{content:"\f1a8"}.fa-drupal:before{content:"\f1a9"}.fa-joomla:before{content:"\f1aa"}.fa-language:before{content:"\f1ab"}.fa-fax:before{content:"\f1ac"}.fa-building:before{content:"\f1ad"}.fa-child:before{content:"\f1ae"}.fa-paw:before{content:"\f1b0"}.fa-spoon:before{content:"\f1b1"}.fa-cube:before{content:"\f1b2"}.fa-cubes:before{content:"\f1b3"}.fa-behance:before{content:"\f1b4"}.fa-behance-square:before{content:"\f1b5"}.fa-steam:before{content:"\f1b6"}.fa-steam-square:before{content:"\f1b7"}.fa-recycle:before{content:"\f1b8"}.fa-automobile:before,.fa-car:before{content:"\f1b9"}.fa-cab:before,.fa-taxi:before{content:"\f1ba"}.fa-tree:before{content:"\f1bb"}.fa-spotify:before{content:"\f1bc"}.fa-deviantart:before{content:"\f1bd"}.fa-soundcloud:before{content:"\f1be"}.fa-database:before{content:"\f1c0"}.fa-file-pdf-o:before{content:"\f1c1"}.fa-file-word-o:before{content:"\f1c2"}.fa-file-excel-o:before{content:"\f1c3"}.fa-file-powerpoint-o:before{content:"\f1c4"}.fa-file-photo-o:before,.fa-file-picture-o:before,.fa-file-image-o:before{content:"\f1c5"}.fa-file-zip-o:before,.fa-file-archive-o:before{content:"\f1c6"}.fa-file-sound-o:before,.fa-file-audio-o:before{content:"\f1c7"}.fa-file-movie-o:before,.fa-file-video-o:before{content:"\f1c8"}.fa-file-code-o:before{content:"\f1c9"}.fa-vine:before{content:"\f1ca"}.fa-codepen:before{content:"\f1cb"}.fa-jsfiddle:before{content:"\f1cc"}.fa-life-bouy:before,.fa-life-buoy:before,.fa-life-saver:before,.fa-support:before,.fa-life-ring:before{content:"\f1cd"}.fa-circle-o-notch:before{content:"\f1ce"}.fa-ra:before,.fa-rebel:before{content:"\f1d0"}.fa-ge:before,.fa-empire:before{content:"\f1d1"}.fa-git-square:before{content:"\f1d2"}.fa-git:before{content:"\f1d3"}.fa-y-combinator-square:before,.fa-yc-square:before,.fa-hacker-news:before{content:"\f1d4"}.fa-tencent-weibo:before{content:"\f1d5"}.fa-qq:before{content:"\f1d6"}.fa-wechat:before,.fa-weixin:before{content:"\f1d7"}.fa-send:before,.fa-paper-plane:before{content:"\f1d8"}.fa-send-o:before,.fa-paper-plane-o:before{content:"\f1d9"}.fa-history:before{content:"\f1da"}.fa-circle-thin:before{content:"\f1db"}.fa-header:before{content:"\f1dc"}.fa-paragraph:before{content:"\f1dd"}.fa-sliders:before{content:"\f1de"}.fa-share-alt:before{content:"\f1e0"}.fa-share-alt-square:before{content:"\f1e1"}.fa-bomb:before{content:"\f1e2"}.fa-soccer-ball-o:before,.fa-futbol-o:before{content:"\f1e3"}.fa-tty:before{content:"\f1e4"}.fa-binoculars:before{content:"\f1e5"}.fa-plug:before{content:"\f1e6"}.fa-slideshare:before{content:"\f1e7"}.fa-twitch:before{content:"\f1e8"}.fa-yelp:before{content:"\f1e9"}.fa-newspaper-o:before{content:"\f1ea"}.fa-wifi:before{content:"\f1eb"}.fa-calculator:before{content:"\f1ec"}.fa-paypal:before{content:"\f1ed"}.fa-google-wallet:before{content:"\f1ee"}.fa-cc-visa:before{content:"\f1f0"}.fa-cc-mastercard:before{content:"\f1f1"}.fa-cc-discover:before{content:"\f1f2"}.fa-cc-amex:before{content:"\f1f3"}.fa-cc-paypal:before{content:"\f1f4"}.fa-cc-stripe:before{content:"\f1f5"}.fa-bell-slash:before{content:"\f1f6"}.fa-bell-slash-o:before{content:"\f1f7"}.fa-trash:before{content:"\f1f8"}.fa-copyright:before{content:"\f1f9"}.fa-at:before{content:"\f1fa"}.fa-eyedropper:before{content:"\f1fb"}.fa-paint-brush:before{content:"\f1fc"}.fa-birthday-cake:before{content:"\f1fd"}.fa-area-chart:before{content:"\f1fe"}.fa-pie-chart:before{content:"\f200"}.fa-line-chart:before{content:"\f201"}.fa-lastfm:before{content:"\f202"}.fa-lastfm-square:before{content:"\f203"}.fa-toggle-off:before{content:"\f204"}.fa-toggle-on:before{content:"\f205"}.fa-bicycle:before{content:"\f206"}.fa-bus:before{content:"\f207"}.fa-ioxhost:before{content:"\f208"}.fa-angellist:before{content:"\f209"}.fa-cc:before{content:"\f20a"}.fa-shekel:before,.fa-sheqel:before,.fa-ils:before{content:"\f20b"}.fa-meanpath:before{content:"\f20c"}.fa-buysellads:before{content:"\f20d"}.fa-connectdevelop:before{content:"\f20e"}.fa-dashcube:before{content:"\f210"}.fa-forumbee:before{content:"\f211"}.fa-leanpub:before{content:"\f212"}.fa-sellsy:before{content:"\f213"}.fa-shirtsinbulk:before{content:"\f214"}.fa-simplybuilt:before{content:"\f215"}.fa-skyatlas:before{content:"\f216"}.fa-cart-plus:before{content:"\f217"}.fa-cart-arrow-down:before{content:"\f218"}.fa-diamond:before{content:"\f219"}.fa-ship:before{content:"\f21a"}.fa-user-secret:before{content:"\f21b"}.fa-motorcycle:before{content:"\f21c"}.fa-street-view:before{content:"\f21d"}.fa-heartbeat:before{content:"\f21e"}.fa-venus:before{content:"\f221"}.fa-mars:before{content:"\f222"}.fa-mercury:before{content:"\f223"}.fa-intersex:before,.fa-transgender:before{content:"\f224"}.fa-transgender-alt:before{content:"\f225"}.fa-venus-double:before{content:"\f226"}.fa-mars-double:before{content:"\f227"}.fa-venus-mars:before{content:"\f228"}.fa-mars-stroke:before{content:"\f229"}.fa-mars-stroke-v:before{content:"\f22a"}.fa-mars-stroke-h:before{content:"\f22b"}.fa-neuter:before{content:"\f22c"}.fa-genderless:before{content:"\f22d"}.fa-facebook-official:before{content:"\f230"}.fa-pinterest-p:before{content:"\f231"}.fa-whatsapp:before{content:"\f232"}.fa-server:before{content:"\f233"}.fa-user-plus:before{content:"\f234"}.fa-user-times:before{content:"\f235"}.fa-hotel:before,.fa-bed:before{content:"\f236"}.fa-viacoin:before{content:"\f237"}.fa-train:before{content:"\f238"}.fa-subway:before{content:"\f239"}.fa-medium:before{content:"\f23a"}.fa-yc:before,.fa-y-combinator:before{content:"\f23b"}.fa-optin-monster:before{content:"\f23c"}.fa-opencart:before{content:"\f23d"}.fa-expeditedssl:before{content:"\f23e"}.fa-battery-4:before,.fa-battery-full:before{content:"\f240"}.fa-battery-3:before,.fa-battery-three-quarters:before{content:"\f241"}.fa-battery-2:before,.fa-battery-half:before{content:"\f242"}.fa-battery-1:before,.fa-battery-quarter:before{content:"\f243"}.fa-battery-0:before,.fa-battery-empty:before{content:"\f244"}.fa-mouse-pointer:before{content:"\f245"}.fa-i-cursor:before{content:"\f246"}.fa-object-group:before{content:"\f247"}.fa-object-ungroup:before{content:"\f248"}.fa-sticky-note:before{content:"\f249"}.fa-sticky-note-o:before{content:"\f24a"}.fa-cc-jcb:before{content:"\f24b"}.fa-cc-diners-club:before{content:"\f24c"}.fa-clone:before{content:"\f24d"}.fa-balance-scale:before{content:"\f24e"}.fa-hourglass-o:before{content:"\f250"}.fa-hourglass-1:before,.fa-hourglass-start:before{content:"\f251"}.fa-hourglass-2:before,.fa-hourglass-half:before{content:"\f252"}.fa-hourglass-3:before,.fa-hourglass-end:before{content:"\f253"}.fa-hourglass:before{content:"\f254"}.fa-hand-grab-o:before,.fa-hand-rock-o:before{content:"\f255"}.fa-hand-stop-o:before,.fa-hand-paper-o:before{content:"\f256"}.fa-hand-scissors-o:before{content:"\f257"}.fa-hand-lizard-o:before{content:"\f258"}.fa-hand-spock-o:before{content:"\f259"}.fa-hand-pointer-o:before{content:"\f25a"}.fa-hand-peace-o:before{content:"\f25b"}.fa-trademark:before{content:"\f25c"}.fa-registered:before{content:"\f25d"}.fa-creative-commons:before{content:"\f25e"}.fa-gg:before{content:"\f260"}.fa-gg-circle:before{content:"\f261"}.fa-tripadvisor:before{content:"\f262"}.fa-odnoklassniki:before{content:"\f263"}.fa-odnoklassniki-square:before{content:"\f264"}.fa-get-pocket:before{content:"\f265"}.fa-wikipedia-w:before{content:"\f266"}.fa-safari:before{content:"\f267"}.fa-chrome:before{content:"\f268"}.fa-firefox:before{content:"\f269"}.fa-opera:before{content:"\f26a"}.fa-internet-explorer:before{content:"\f26b"}.fa-tv:before,.fa-television:before{content:"\f26c"}.fa-contao:before{content:"\f26d"}.fa-500px:before{content:"\f26e"}.fa-amazon:before{content:"\f270"}.fa-calendar-plus-o:before{content:"\f271"}.fa-calendar-minus-o:before{content:"\f272"}.fa-calendar-times-o:before{content:"\f273"}.fa-calendar-check-o:before{content:"\f274"}.fa-industry:before{content:"\f275"}.fa-map-pin:before{content:"\f276"}.fa-map-signs:before{content:"\f277"}.fa-map-o:before{content:"\f278"}.fa-map:before{content:"\f279"}.fa-commenting:before{content:"\f27a"}.fa-commenting-o:before{content:"\f27b"}.fa-houzz:before{content:"\f27c"}.fa-vimeo:before{content:"\f27d"}.fa-black-tie:before{content:"\f27e"}.fa-fonticons:before{content:"\f280"}.fa-reddit-alien:before{content:"\f281"}.fa-edge:before{content:"\f282"}.fa-credit-card-alt:before{content:"\f283"}.fa-codiepie:before{content:"\f284"}.fa-modx:before{content:"\f285"}.fa-fort-awesome:before{content:"\f286"}.fa-usb:before{content:"\f287"}.fa-product-hunt:before{content:"\f288"}.fa-mixcloud:before{content:"\f289"}.fa-scribd:before{content:"\f28a"}.fa-pause-circle:before{content:"\f28b"}.fa-pause-circle-o:before{content:"\f28c"}.fa-stop-circle:before{content:"\f28d"}.fa-stop-circle-o:before{content:"\f28e"}.fa-shopping-bag:before{content:"\f290"}.fa-shopping-basket:before{content:"\f291"}.fa-hashtag:before{content:"\f292"}.fa-bluetooth:before{content:"\f293"}.fa-bluetooth-b:before{content:"\f294"}.fa-percent:before{content:"\f295"} + */@font-face{font-family:'FontAwesome';src:url('../fonts/fontawesome-webfont.eot?v=4.7.0');src:url('../fonts/fontawesome-webfont.eot?#iefix&v=4.7.0') format('embedded-opentype'),url('../fonts/fontawesome-webfont.woff2?v=4.7.0') format('woff2'),url('../fonts/fontawesome-webfont.woff?v=4.7.0') format('woff'),url('../fonts/fontawesome-webfont.ttf?v=4.7.0') format('truetype'),url('../fonts/fontawesome-webfont.svg?v=4.7.0#fontawesomeregular') format('svg');font-weight:normal;font-style:normal}.fa{display:inline-block;font:normal normal normal 14px/1 FontAwesome;font-size:inherit;text-rendering:auto;-webkit-font-smoothing:antialiased;-moz-osx-font-smoothing:grayscale}.fa-lg{font-size:1.33333333em;line-height:.75em;vertical-align:-15%}.fa-2x{font-size:2em}.fa-3x{font-size:3em}.fa-4x{font-size:4em}.fa-5x{font-size:5em}.fa-fw{width:1.28571429em;text-align:center}.fa-ul{padding-left:0;margin-left:2.14285714em;list-style-type:none}.fa-ul>li{position:relative}.fa-li{position:absolute;left:-2.14285714em;width:2.14285714em;top:.14285714em;text-align:center}.fa-li.fa-lg{left:-1.85714286em}.fa-border{padding:.2em .25em .15em;border:solid .08em #eee;border-radius:.1em}.fa-pull-left{float:left}.fa-pull-right{float:right}.fa.fa-pull-left{margin-right:.3em}.fa.fa-pull-right{margin-left:.3em}.pull-right{float:right}.pull-left{float:left}.fa.pull-left{margin-right:.3em}.fa.pull-right{margin-left:.3em}.fa-spin{-webkit-animation:fa-spin 2s infinite linear;animation:fa-spin 2s infinite linear}.fa-pulse{-webkit-animation:fa-spin 1s infinite steps(8);animation:fa-spin 1s infinite steps(8)}@-webkit-keyframes fa-spin{0%{-webkit-transform:rotate(0deg);transform:rotate(0deg)}100%{-webkit-transform:rotate(359deg);transform:rotate(359deg)}}@keyframes fa-spin{0%{-webkit-transform:rotate(0deg);transform:rotate(0deg)}100%{-webkit-transform:rotate(359deg);transform:rotate(359deg)}}.fa-rotate-90{-ms-filter:"progid:DXImageTransform.Microsoft.BasicImage(rotation=1)";-webkit-transform:rotate(90deg);-ms-transform:rotate(90deg);transform:rotate(90deg)}.fa-rotate-180{-ms-filter:"progid:DXImageTransform.Microsoft.BasicImage(rotation=2)";-webkit-transform:rotate(180deg);-ms-transform:rotate(180deg);transform:rotate(180deg)}.fa-rotate-270{-ms-filter:"progid:DXImageTransform.Microsoft.BasicImage(rotation=3)";-webkit-transform:rotate(270deg);-ms-transform:rotate(270deg);transform:rotate(270deg)}.fa-flip-horizontal{-ms-filter:"progid:DXImageTransform.Microsoft.BasicImage(rotation=0, mirror=1)";-webkit-transform:scale(-1, 1);-ms-transform:scale(-1, 1);transform:scale(-1, 1)}.fa-flip-vertical{-ms-filter:"progid:DXImageTransform.Microsoft.BasicImage(rotation=2, mirror=1)";-webkit-transform:scale(1, -1);-ms-transform:scale(1, -1);transform:scale(1, -1)}:root .fa-rotate-90,:root .fa-rotate-180,:root .fa-rotate-270,:root .fa-flip-horizontal,:root .fa-flip-vertical{filter:none}.fa-stack{position:relative;display:inline-block;width:2em;height:2em;line-height:2em;vertical-align:middle}.fa-stack-1x,.fa-stack-2x{position:absolute;left:0;width:100%;text-align:center}.fa-stack-1x{line-height:inherit}.fa-stack-2x{font-size:2em}.fa-inverse{color:#fff}.fa-glass:before{content:"\f000"}.fa-music:before{content:"\f001"}.fa-search:before{content:"\f002"}.fa-envelope-o:before{content:"\f003"}.fa-heart:before{content:"\f004"}.fa-star:before{content:"\f005"}.fa-star-o:before{content:"\f006"}.fa-user:before{content:"\f007"}.fa-film:before{content:"\f008"}.fa-th-large:before{content:"\f009"}.fa-th:before{content:"\f00a"}.fa-th-list:before{content:"\f00b"}.fa-check:before{content:"\f00c"}.fa-remove:before,.fa-close:before,.fa-times:before{content:"\f00d"}.fa-search-plus:before{content:"\f00e"}.fa-search-minus:before{content:"\f010"}.fa-power-off:before{content:"\f011"}.fa-signal:before{content:"\f012"}.fa-gear:before,.fa-cog:before{content:"\f013"}.fa-trash-o:before{content:"\f014"}.fa-home:before{content:"\f015"}.fa-file-o:before{content:"\f016"}.fa-clock-o:before{content:"\f017"}.fa-road:before{content:"\f018"}.fa-download:before{content:"\f019"}.fa-arrow-circle-o-down:before{content:"\f01a"}.fa-arrow-circle-o-up:before{content:"\f01b"}.fa-inbox:before{content:"\f01c"}.fa-play-circle-o:before{content:"\f01d"}.fa-rotate-right:before,.fa-repeat:before{content:"\f01e"}.fa-refresh:before{content:"\f021"}.fa-list-alt:before{content:"\f022"}.fa-lock:before{content:"\f023"}.fa-flag:before{content:"\f024"}.fa-headphones:before{content:"\f025"}.fa-volume-off:before{content:"\f026"}.fa-volume-down:before{content:"\f027"}.fa-volume-up:before{content:"\f028"}.fa-qrcode:before{content:"\f029"}.fa-barcode:before{content:"\f02a"}.fa-tag:before{content:"\f02b"}.fa-tags:before{content:"\f02c"}.fa-book:before{content:"\f02d"}.fa-bookmark:before{content:"\f02e"}.fa-print:before{content:"\f02f"}.fa-camera:before{content:"\f030"}.fa-font:before{content:"\f031"}.fa-bold:before{content:"\f032"}.fa-italic:before{content:"\f033"}.fa-text-height:before{content:"\f034"}.fa-text-width:before{content:"\f035"}.fa-align-left:before{content:"\f036"}.fa-align-center:before{content:"\f037"}.fa-align-right:before{content:"\f038"}.fa-align-justify:before{content:"\f039"}.fa-list:before{content:"\f03a"}.fa-dedent:before,.fa-outdent:before{content:"\f03b"}.fa-indent:before{content:"\f03c"}.fa-video-camera:before{content:"\f03d"}.fa-photo:before,.fa-image:before,.fa-picture-o:before{content:"\f03e"}.fa-pencil:before{content:"\f040"}.fa-map-marker:before{content:"\f041"}.fa-adjust:before{content:"\f042"}.fa-tint:before{content:"\f043"}.fa-edit:before,.fa-pencil-square-o:before{content:"\f044"}.fa-share-square-o:before{content:"\f045"}.fa-check-square-o:before{content:"\f046"}.fa-arrows:before{content:"\f047"}.fa-step-backward:before{content:"\f048"}.fa-fast-backward:before{content:"\f049"}.fa-backward:before{content:"\f04a"}.fa-play:before{content:"\f04b"}.fa-pause:before{content:"\f04c"}.fa-stop:before{content:"\f04d"}.fa-forward:before{content:"\f04e"}.fa-fast-forward:before{content:"\f050"}.fa-step-forward:before{content:"\f051"}.fa-eject:before{content:"\f052"}.fa-chevron-left:before{content:"\f053"}.fa-chevron-right:before{content:"\f054"}.fa-plus-circle:before{content:"\f055"}.fa-minus-circle:before{content:"\f056"}.fa-times-circle:before{content:"\f057"}.fa-check-circle:before{content:"\f058"}.fa-question-circle:before{content:"\f059"}.fa-info-circle:before{content:"\f05a"}.fa-crosshairs:before{content:"\f05b"}.fa-times-circle-o:before{content:"\f05c"}.fa-check-circle-o:before{content:"\f05d"}.fa-ban:before{content:"\f05e"}.fa-arrow-left:before{content:"\f060"}.fa-arrow-right:before{content:"\f061"}.fa-arrow-up:before{content:"\f062"}.fa-arrow-down:before{content:"\f063"}.fa-mail-forward:before,.fa-share:before{content:"\f064"}.fa-expand:before{content:"\f065"}.fa-compress:before{content:"\f066"}.fa-plus:before{content:"\f067"}.fa-minus:before{content:"\f068"}.fa-asterisk:before{content:"\f069"}.fa-exclamation-circle:before{content:"\f06a"}.fa-gift:before{content:"\f06b"}.fa-leaf:before{content:"\f06c"}.fa-fire:before{content:"\f06d"}.fa-eye:before{content:"\f06e"}.fa-eye-slash:before{content:"\f070"}.fa-warning:before,.fa-exclamation-triangle:before{content:"\f071"}.fa-plane:before{content:"\f072"}.fa-calendar:before{content:"\f073"}.fa-random:before{content:"\f074"}.fa-comment:before{content:"\f075"}.fa-magnet:before{content:"\f076"}.fa-chevron-up:before{content:"\f077"}.fa-chevron-down:before{content:"\f078"}.fa-retweet:before{content:"\f079"}.fa-shopping-cart:before{content:"\f07a"}.fa-folder:before{content:"\f07b"}.fa-folder-open:before{content:"\f07c"}.fa-arrows-v:before{content:"\f07d"}.fa-arrows-h:before{content:"\f07e"}.fa-bar-chart-o:before,.fa-bar-chart:before{content:"\f080"}.fa-twitter-square:before{content:"\f081"}.fa-facebook-square:before{content:"\f082"}.fa-camera-retro:before{content:"\f083"}.fa-key:before{content:"\f084"}.fa-gears:before,.fa-cogs:before{content:"\f085"}.fa-comments:before{content:"\f086"}.fa-thumbs-o-up:before{content:"\f087"}.fa-thumbs-o-down:before{content:"\f088"}.fa-star-half:before{content:"\f089"}.fa-heart-o:before{content:"\f08a"}.fa-sign-out:before{content:"\f08b"}.fa-linkedin-square:before{content:"\f08c"}.fa-thumb-tack:before{content:"\f08d"}.fa-external-link:before{content:"\f08e"}.fa-sign-in:before{content:"\f090"}.fa-trophy:before{content:"\f091"}.fa-github-square:before{content:"\f092"}.fa-upload:before{content:"\f093"}.fa-lemon-o:before{content:"\f094"}.fa-phone:before{content:"\f095"}.fa-square-o:before{content:"\f096"}.fa-bookmark-o:before{content:"\f097"}.fa-phone-square:before{content:"\f098"}.fa-twitter:before{content:"\f099"}.fa-facebook-f:before,.fa-facebook:before{content:"\f09a"}.fa-github:before{content:"\f09b"}.fa-unlock:before{content:"\f09c"}.fa-credit-card:before{content:"\f09d"}.fa-feed:before,.fa-rss:before{content:"\f09e"}.fa-hdd-o:before{content:"\f0a0"}.fa-bullhorn:before{content:"\f0a1"}.fa-bell:before{content:"\f0f3"}.fa-certificate:before{content:"\f0a3"}.fa-hand-o-right:before{content:"\f0a4"}.fa-hand-o-left:before{content:"\f0a5"}.fa-hand-o-up:before{content:"\f0a6"}.fa-hand-o-down:before{content:"\f0a7"}.fa-arrow-circle-left:before{content:"\f0a8"}.fa-arrow-circle-right:before{content:"\f0a9"}.fa-arrow-circle-up:before{content:"\f0aa"}.fa-arrow-circle-down:before{content:"\f0ab"}.fa-globe:before{content:"\f0ac"}.fa-wrench:before{content:"\f0ad"}.fa-tasks:before{content:"\f0ae"}.fa-filter:before{content:"\f0b0"}.fa-briefcase:before{content:"\f0b1"}.fa-arrows-alt:before{content:"\f0b2"}.fa-group:before,.fa-users:before{content:"\f0c0"}.fa-chain:before,.fa-link:before{content:"\f0c1"}.fa-cloud:before{content:"\f0c2"}.fa-flask:before{content:"\f0c3"}.fa-cut:before,.fa-scissors:before{content:"\f0c4"}.fa-copy:before,.fa-files-o:before{content:"\f0c5"}.fa-paperclip:before{content:"\f0c6"}.fa-save:before,.fa-floppy-o:before{content:"\f0c7"}.fa-square:before{content:"\f0c8"}.fa-navicon:before,.fa-reorder:before,.fa-bars:before{content:"\f0c9"}.fa-list-ul:before{content:"\f0ca"}.fa-list-ol:before{content:"\f0cb"}.fa-strikethrough:before{content:"\f0cc"}.fa-underline:before{content:"\f0cd"}.fa-table:before{content:"\f0ce"}.fa-magic:before{content:"\f0d0"}.fa-truck:before{content:"\f0d1"}.fa-pinterest:before{content:"\f0d2"}.fa-pinterest-square:before{content:"\f0d3"}.fa-google-plus-square:before{content:"\f0d4"}.fa-google-plus:before{content:"\f0d5"}.fa-money:before{content:"\f0d6"}.fa-caret-down:before{content:"\f0d7"}.fa-caret-up:before{content:"\f0d8"}.fa-caret-left:before{content:"\f0d9"}.fa-caret-right:before{content:"\f0da"}.fa-columns:before{content:"\f0db"}.fa-unsorted:before,.fa-sort:before{content:"\f0dc"}.fa-sort-down:before,.fa-sort-desc:before{content:"\f0dd"}.fa-sort-up:before,.fa-sort-asc:before{content:"\f0de"}.fa-envelope:before{content:"\f0e0"}.fa-linkedin:before{content:"\f0e1"}.fa-rotate-left:before,.fa-undo:before{content:"\f0e2"}.fa-legal:before,.fa-gavel:before{content:"\f0e3"}.fa-dashboard:before,.fa-tachometer:before{content:"\f0e4"}.fa-comment-o:before{content:"\f0e5"}.fa-comments-o:before{content:"\f0e6"}.fa-flash:before,.fa-bolt:before{content:"\f0e7"}.fa-sitemap:before{content:"\f0e8"}.fa-umbrella:before{content:"\f0e9"}.fa-paste:before,.fa-clipboard:before{content:"\f0ea"}.fa-lightbulb-o:before{content:"\f0eb"}.fa-exchange:before{content:"\f0ec"}.fa-cloud-download:before{content:"\f0ed"}.fa-cloud-upload:before{content:"\f0ee"}.fa-user-md:before{content:"\f0f0"}.fa-stethoscope:before{content:"\f0f1"}.fa-suitcase:before{content:"\f0f2"}.fa-bell-o:before{content:"\f0a2"}.fa-coffee:before{content:"\f0f4"}.fa-cutlery:before{content:"\f0f5"}.fa-file-text-o:before{content:"\f0f6"}.fa-building-o:before{content:"\f0f7"}.fa-hospital-o:before{content:"\f0f8"}.fa-ambulance:before{content:"\f0f9"}.fa-medkit:before{content:"\f0fa"}.fa-fighter-jet:before{content:"\f0fb"}.fa-beer:before{content:"\f0fc"}.fa-h-square:before{content:"\f0fd"}.fa-plus-square:before{content:"\f0fe"}.fa-angle-double-left:before{content:"\f100"}.fa-angle-double-right:before{content:"\f101"}.fa-angle-double-up:before{content:"\f102"}.fa-angle-double-down:before{content:"\f103"}.fa-angle-left:before{content:"\f104"}.fa-angle-right:before{content:"\f105"}.fa-angle-up:before{content:"\f106"}.fa-angle-down:before{content:"\f107"}.fa-desktop:before{content:"\f108"}.fa-laptop:before{content:"\f109"}.fa-tablet:before{content:"\f10a"}.fa-mobile-phone:before,.fa-mobile:before{content:"\f10b"}.fa-circle-o:before{content:"\f10c"}.fa-quote-left:before{content:"\f10d"}.fa-quote-right:before{content:"\f10e"}.fa-spinner:before{content:"\f110"}.fa-circle:before{content:"\f111"}.fa-mail-reply:before,.fa-reply:before{content:"\f112"}.fa-github-alt:before{content:"\f113"}.fa-folder-o:before{content:"\f114"}.fa-folder-open-o:before{content:"\f115"}.fa-smile-o:before{content:"\f118"}.fa-frown-o:before{content:"\f119"}.fa-meh-o:before{content:"\f11a"}.fa-gamepad:before{content:"\f11b"}.fa-keyboard-o:before{content:"\f11c"}.fa-flag-o:before{content:"\f11d"}.fa-flag-checkered:before{content:"\f11e"}.fa-terminal:before{content:"\f120"}.fa-code:before{content:"\f121"}.fa-mail-reply-all:before,.fa-reply-all:before{content:"\f122"}.fa-star-half-empty:before,.fa-star-half-full:before,.fa-star-half-o:before{content:"\f123"}.fa-location-arrow:before{content:"\f124"}.fa-crop:before{content:"\f125"}.fa-code-fork:before{content:"\f126"}.fa-unlink:before,.fa-chain-broken:before{content:"\f127"}.fa-question:before{content:"\f128"}.fa-info:before{content:"\f129"}.fa-exclamation:before{content:"\f12a"}.fa-superscript:before{content:"\f12b"}.fa-subscript:before{content:"\f12c"}.fa-eraser:before{content:"\f12d"}.fa-puzzle-piece:before{content:"\f12e"}.fa-microphone:before{content:"\f130"}.fa-microphone-slash:before{content:"\f131"}.fa-shield:before{content:"\f132"}.fa-calendar-o:before{content:"\f133"}.fa-fire-extinguisher:before{content:"\f134"}.fa-rocket:before{content:"\f135"}.fa-maxcdn:before{content:"\f136"}.fa-chevron-circle-left:before{content:"\f137"}.fa-chevron-circle-right:before{content:"\f138"}.fa-chevron-circle-up:before{content:"\f139"}.fa-chevron-circle-down:before{content:"\f13a"}.fa-html5:before{content:"\f13b"}.fa-css3:before{content:"\f13c"}.fa-anchor:before{content:"\f13d"}.fa-unlock-alt:before{content:"\f13e"}.fa-bullseye:before{content:"\f140"}.fa-ellipsis-h:before{content:"\f141"}.fa-ellipsis-v:before{content:"\f142"}.fa-rss-square:before{content:"\f143"}.fa-play-circle:before{content:"\f144"}.fa-ticket:before{content:"\f145"}.fa-minus-square:before{content:"\f146"}.fa-minus-square-o:before{content:"\f147"}.fa-level-up:before{content:"\f148"}.fa-level-down:before{content:"\f149"}.fa-check-square:before{content:"\f14a"}.fa-pencil-square:before{content:"\f14b"}.fa-external-link-square:before{content:"\f14c"}.fa-share-square:before{content:"\f14d"}.fa-compass:before{content:"\f14e"}.fa-toggle-down:before,.fa-caret-square-o-down:before{content:"\f150"}.fa-toggle-up:before,.fa-caret-square-o-up:before{content:"\f151"}.fa-toggle-right:before,.fa-caret-square-o-right:before{content:"\f152"}.fa-euro:before,.fa-eur:before{content:"\f153"}.fa-gbp:before{content:"\f154"}.fa-dollar:before,.fa-usd:before{content:"\f155"}.fa-rupee:before,.fa-inr:before{content:"\f156"}.fa-cny:before,.fa-rmb:before,.fa-yen:before,.fa-jpy:before{content:"\f157"}.fa-ruble:before,.fa-rouble:before,.fa-rub:before{content:"\f158"}.fa-won:before,.fa-krw:before{content:"\f159"}.fa-bitcoin:before,.fa-btc:before{content:"\f15a"}.fa-file:before{content:"\f15b"}.fa-file-text:before{content:"\f15c"}.fa-sort-alpha-asc:before{content:"\f15d"}.fa-sort-alpha-desc:before{content:"\f15e"}.fa-sort-amount-asc:before{content:"\f160"}.fa-sort-amount-desc:before{content:"\f161"}.fa-sort-numeric-asc:before{content:"\f162"}.fa-sort-numeric-desc:before{content:"\f163"}.fa-thumbs-up:before{content:"\f164"}.fa-thumbs-down:before{content:"\f165"}.fa-youtube-square:before{content:"\f166"}.fa-youtube:before{content:"\f167"}.fa-xing:before{content:"\f168"}.fa-xing-square:before{content:"\f169"}.fa-youtube-play:before{content:"\f16a"}.fa-dropbox:before{content:"\f16b"}.fa-stack-overflow:before{content:"\f16c"}.fa-instagram:before{content:"\f16d"}.fa-flickr:before{content:"\f16e"}.fa-adn:before{content:"\f170"}.fa-bitbucket:before{content:"\f171"}.fa-bitbucket-square:before{content:"\f172"}.fa-tumblr:before{content:"\f173"}.fa-tumblr-square:before{content:"\f174"}.fa-long-arrow-down:before{content:"\f175"}.fa-long-arrow-up:before{content:"\f176"}.fa-long-arrow-left:before{content:"\f177"}.fa-long-arrow-right:before{content:"\f178"}.fa-apple:before{content:"\f179"}.fa-windows:before{content:"\f17a"}.fa-android:before{content:"\f17b"}.fa-linux:before{content:"\f17c"}.fa-dribbble:before{content:"\f17d"}.fa-skype:before{content:"\f17e"}.fa-foursquare:before{content:"\f180"}.fa-trello:before{content:"\f181"}.fa-female:before{content:"\f182"}.fa-male:before{content:"\f183"}.fa-gittip:before,.fa-gratipay:before{content:"\f184"}.fa-sun-o:before{content:"\f185"}.fa-moon-o:before{content:"\f186"}.fa-archive:before{content:"\f187"}.fa-bug:before{content:"\f188"}.fa-vk:before{content:"\f189"}.fa-weibo:before{content:"\f18a"}.fa-renren:before{content:"\f18b"}.fa-pagelines:before{content:"\f18c"}.fa-stack-exchange:before{content:"\f18d"}.fa-arrow-circle-o-right:before{content:"\f18e"}.fa-arrow-circle-o-left:before{content:"\f190"}.fa-toggle-left:before,.fa-caret-square-o-left:before{content:"\f191"}.fa-dot-circle-o:before{content:"\f192"}.fa-wheelchair:before{content:"\f193"}.fa-vimeo-square:before{content:"\f194"}.fa-turkish-lira:before,.fa-try:before{content:"\f195"}.fa-plus-square-o:before{content:"\f196"}.fa-space-shuttle:before{content:"\f197"}.fa-slack:before{content:"\f198"}.fa-envelope-square:before{content:"\f199"}.fa-wordpress:before{content:"\f19a"}.fa-openid:before{content:"\f19b"}.fa-institution:before,.fa-bank:before,.fa-university:before{content:"\f19c"}.fa-mortar-board:before,.fa-graduation-cap:before{content:"\f19d"}.fa-yahoo:before{content:"\f19e"}.fa-google:before{content:"\f1a0"}.fa-reddit:before{content:"\f1a1"}.fa-reddit-square:before{content:"\f1a2"}.fa-stumbleupon-circle:before{content:"\f1a3"}.fa-stumbleupon:before{content:"\f1a4"}.fa-delicious:before{content:"\f1a5"}.fa-digg:before{content:"\f1a6"}.fa-pied-piper-pp:before{content:"\f1a7"}.fa-pied-piper-alt:before{content:"\f1a8"}.fa-drupal:before{content:"\f1a9"}.fa-joomla:before{content:"\f1aa"}.fa-language:before{content:"\f1ab"}.fa-fax:before{content:"\f1ac"}.fa-building:before{content:"\f1ad"}.fa-child:before{content:"\f1ae"}.fa-paw:before{content:"\f1b0"}.fa-spoon:before{content:"\f1b1"}.fa-cube:before{content:"\f1b2"}.fa-cubes:before{content:"\f1b3"}.fa-behance:before{content:"\f1b4"}.fa-behance-square:before{content:"\f1b5"}.fa-steam:before{content:"\f1b6"}.fa-steam-square:before{content:"\f1b7"}.fa-recycle:before{content:"\f1b8"}.fa-automobile:before,.fa-car:before{content:"\f1b9"}.fa-cab:before,.fa-taxi:before{content:"\f1ba"}.fa-tree:before{content:"\f1bb"}.fa-spotify:before{content:"\f1bc"}.fa-deviantart:before{content:"\f1bd"}.fa-soundcloud:before{content:"\f1be"}.fa-database:before{content:"\f1c0"}.fa-file-pdf-o:before{content:"\f1c1"}.fa-file-word-o:before{content:"\f1c2"}.fa-file-excel-o:before{content:"\f1c3"}.fa-file-powerpoint-o:before{content:"\f1c4"}.fa-file-photo-o:before,.fa-file-picture-o:before,.fa-file-image-o:before{content:"\f1c5"}.fa-file-zip-o:before,.fa-file-archive-o:before{content:"\f1c6"}.fa-file-sound-o:before,.fa-file-audio-o:before{content:"\f1c7"}.fa-file-movie-o:before,.fa-file-video-o:before{content:"\f1c8"}.fa-file-code-o:before{content:"\f1c9"}.fa-vine:before{content:"\f1ca"}.fa-codepen:before{content:"\f1cb"}.fa-jsfiddle:before{content:"\f1cc"}.fa-life-bouy:before,.fa-life-buoy:before,.fa-life-saver:before,.fa-support:before,.fa-life-ring:before{content:"\f1cd"}.fa-circle-o-notch:before{content:"\f1ce"}.fa-ra:before,.fa-resistance:before,.fa-rebel:before{content:"\f1d0"}.fa-ge:before,.fa-empire:before{content:"\f1d1"}.fa-git-square:before{content:"\f1d2"}.fa-git:before{content:"\f1d3"}.fa-y-combinator-square:before,.fa-yc-square:before,.fa-hacker-news:before{content:"\f1d4"}.fa-tencent-weibo:before{content:"\f1d5"}.fa-qq:before{content:"\f1d6"}.fa-wechat:before,.fa-weixin:before{content:"\f1d7"}.fa-send:before,.fa-paper-plane:before{content:"\f1d8"}.fa-send-o:before,.fa-paper-plane-o:before{content:"\f1d9"}.fa-history:before{content:"\f1da"}.fa-circle-thin:before{content:"\f1db"}.fa-header:before{content:"\f1dc"}.fa-paragraph:before{content:"\f1dd"}.fa-sliders:before{content:"\f1de"}.fa-share-alt:before{content:"\f1e0"}.fa-share-alt-square:before{content:"\f1e1"}.fa-bomb:before{content:"\f1e2"}.fa-soccer-ball-o:before,.fa-futbol-o:before{content:"\f1e3"}.fa-tty:before{content:"\f1e4"}.fa-binoculars:before{content:"\f1e5"}.fa-plug:before{content:"\f1e6"}.fa-slideshare:before{content:"\f1e7"}.fa-twitch:before{content:"\f1e8"}.fa-yelp:before{content:"\f1e9"}.fa-newspaper-o:before{content:"\f1ea"}.fa-wifi:before{content:"\f1eb"}.fa-calculator:before{content:"\f1ec"}.fa-paypal:before{content:"\f1ed"}.fa-google-wallet:before{content:"\f1ee"}.fa-cc-visa:before{content:"\f1f0"}.fa-cc-mastercard:before{content:"\f1f1"}.fa-cc-discover:before{content:"\f1f2"}.fa-cc-amex:before{content:"\f1f3"}.fa-cc-paypal:before{content:"\f1f4"}.fa-cc-stripe:before{content:"\f1f5"}.fa-bell-slash:before{content:"\f1f6"}.fa-bell-slash-o:before{content:"\f1f7"}.fa-trash:before{content:"\f1f8"}.fa-copyright:before{content:"\f1f9"}.fa-at:before{content:"\f1fa"}.fa-eyedropper:before{content:"\f1fb"}.fa-paint-brush:before{content:"\f1fc"}.fa-birthday-cake:before{content:"\f1fd"}.fa-area-chart:before{content:"\f1fe"}.fa-pie-chart:before{content:"\f200"}.fa-line-chart:before{content:"\f201"}.fa-lastfm:before{content:"\f202"}.fa-lastfm-square:before{content:"\f203"}.fa-toggle-off:before{content:"\f204"}.fa-toggle-on:before{content:"\f205"}.fa-bicycle:before{content:"\f206"}.fa-bus:before{content:"\f207"}.fa-ioxhost:before{content:"\f208"}.fa-angellist:before{content:"\f209"}.fa-cc:before{content:"\f20a"}.fa-shekel:before,.fa-sheqel:before,.fa-ils:before{content:"\f20b"}.fa-meanpath:before{content:"\f20c"}.fa-buysellads:before{content:"\f20d"}.fa-connectdevelop:before{content:"\f20e"}.fa-dashcube:before{content:"\f210"}.fa-forumbee:before{content:"\f211"}.fa-leanpub:before{content:"\f212"}.fa-sellsy:before{content:"\f213"}.fa-shirtsinbulk:before{content:"\f214"}.fa-simplybuilt:before{content:"\f215"}.fa-skyatlas:before{content:"\f216"}.fa-cart-plus:before{content:"\f217"}.fa-cart-arrow-down:before{content:"\f218"}.fa-diamond:before{content:"\f219"}.fa-ship:before{content:"\f21a"}.fa-user-secret:before{content:"\f21b"}.fa-motorcycle:before{content:"\f21c"}.fa-street-view:before{content:"\f21d"}.fa-heartbeat:before{content:"\f21e"}.fa-venus:before{content:"\f221"}.fa-mars:before{content:"\f222"}.fa-mercury:before{content:"\f223"}.fa-intersex:before,.fa-transgender:before{content:"\f224"}.fa-transgender-alt:before{content:"\f225"}.fa-venus-double:before{content:"\f226"}.fa-mars-double:before{content:"\f227"}.fa-venus-mars:before{content:"\f228"}.fa-mars-stroke:before{content:"\f229"}.fa-mars-stroke-v:before{content:"\f22a"}.fa-mars-stroke-h:before{content:"\f22b"}.fa-neuter:before{content:"\f22c"}.fa-genderless:before{content:"\f22d"}.fa-facebook-official:before{content:"\f230"}.fa-pinterest-p:before{content:"\f231"}.fa-whatsapp:before{content:"\f232"}.fa-server:before{content:"\f233"}.fa-user-plus:before{content:"\f234"}.fa-user-times:before{content:"\f235"}.fa-hotel:before,.fa-bed:before{content:"\f236"}.fa-viacoin:before{content:"\f237"}.fa-train:before{content:"\f238"}.fa-subway:before{content:"\f239"}.fa-medium:before{content:"\f23a"}.fa-yc:before,.fa-y-combinator:before{content:"\f23b"}.fa-optin-monster:before{content:"\f23c"}.fa-opencart:before{content:"\f23d"}.fa-expeditedssl:before{content:"\f23e"}.fa-battery-4:before,.fa-battery:before,.fa-battery-full:before{content:"\f240"}.fa-battery-3:before,.fa-battery-three-quarters:before{content:"\f241"}.fa-battery-2:before,.fa-battery-half:before{content:"\f242"}.fa-battery-1:before,.fa-battery-quarter:before{content:"\f243"}.fa-battery-0:before,.fa-battery-empty:before{content:"\f244"}.fa-mouse-pointer:before{content:"\f245"}.fa-i-cursor:before{content:"\f246"}.fa-object-group:before{content:"\f247"}.fa-object-ungroup:before{content:"\f248"}.fa-sticky-note:before{content:"\f249"}.fa-sticky-note-o:before{content:"\f24a"}.fa-cc-jcb:before{content:"\f24b"}.fa-cc-diners-club:before{content:"\f24c"}.fa-clone:before{content:"\f24d"}.fa-balance-scale:before{content:"\f24e"}.fa-hourglass-o:before{content:"\f250"}.fa-hourglass-1:before,.fa-hourglass-start:before{content:"\f251"}.fa-hourglass-2:before,.fa-hourglass-half:before{content:"\f252"}.fa-hourglass-3:before,.fa-hourglass-end:before{content:"\f253"}.fa-hourglass:before{content:"\f254"}.fa-hand-grab-o:before,.fa-hand-rock-o:before{content:"\f255"}.fa-hand-stop-o:before,.fa-hand-paper-o:before{content:"\f256"}.fa-hand-scissors-o:before{content:"\f257"}.fa-hand-lizard-o:before{content:"\f258"}.fa-hand-spock-o:before{content:"\f259"}.fa-hand-pointer-o:before{content:"\f25a"}.fa-hand-peace-o:before{content:"\f25b"}.fa-trademark:before{content:"\f25c"}.fa-registered:before{content:"\f25d"}.fa-creative-commons:before{content:"\f25e"}.fa-gg:before{content:"\f260"}.fa-gg-circle:before{content:"\f261"}.fa-tripadvisor:before{content:"\f262"}.fa-odnoklassniki:before{content:"\f263"}.fa-odnoklassniki-square:before{content:"\f264"}.fa-get-pocket:before{content:"\f265"}.fa-wikipedia-w:before{content:"\f266"}.fa-safari:before{content:"\f267"}.fa-chrome:before{content:"\f268"}.fa-firefox:before{content:"\f269"}.fa-opera:before{content:"\f26a"}.fa-internet-explorer:before{content:"\f26b"}.fa-tv:before,.fa-television:before{content:"\f26c"}.fa-contao:before{content:"\f26d"}.fa-500px:before{content:"\f26e"}.fa-amazon:before{content:"\f270"}.fa-calendar-plus-o:before{content:"\f271"}.fa-calendar-minus-o:before{content:"\f272"}.fa-calendar-times-o:before{content:"\f273"}.fa-calendar-check-o:before{content:"\f274"}.fa-industry:before{content:"\f275"}.fa-map-pin:before{content:"\f276"}.fa-map-signs:before{content:"\f277"}.fa-map-o:before{content:"\f278"}.fa-map:before{content:"\f279"}.fa-commenting:before{content:"\f27a"}.fa-commenting-o:before{content:"\f27b"}.fa-houzz:before{content:"\f27c"}.fa-vimeo:before{content:"\f27d"}.fa-black-tie:before{content:"\f27e"}.fa-fonticons:before{content:"\f280"}.fa-reddit-alien:before{content:"\f281"}.fa-edge:before{content:"\f282"}.fa-credit-card-alt:before{content:"\f283"}.fa-codiepie:before{content:"\f284"}.fa-modx:before{content:"\f285"}.fa-fort-awesome:before{content:"\f286"}.fa-usb:before{content:"\f287"}.fa-product-hunt:before{content:"\f288"}.fa-mixcloud:before{content:"\f289"}.fa-scribd:before{content:"\f28a"}.fa-pause-circle:before{content:"\f28b"}.fa-pause-circle-o:before{content:"\f28c"}.fa-stop-circle:before{content:"\f28d"}.fa-stop-circle-o:before{content:"\f28e"}.fa-shopping-bag:before{content:"\f290"}.fa-shopping-basket:before{content:"\f291"}.fa-hashtag:before{content:"\f292"}.fa-bluetooth:before{content:"\f293"}.fa-bluetooth-b:before{content:"\f294"}.fa-percent:before{content:"\f295"}.fa-gitlab:before{content:"\f296"}.fa-wpbeginner:before{content:"\f297"}.fa-wpforms:before{content:"\f298"}.fa-envira:before{content:"\f299"}.fa-universal-access:before{content:"\f29a"}.fa-wheelchair-alt:before{content:"\f29b"}.fa-question-circle-o:before{content:"\f29c"}.fa-blind:before{content:"\f29d"}.fa-audio-description:before{content:"\f29e"}.fa-volume-control-phone:before{content:"\f2a0"}.fa-braille:before{content:"\f2a1"}.fa-assistive-listening-systems:before{content:"\f2a2"}.fa-asl-interpreting:before,.fa-american-sign-language-interpreting:before{content:"\f2a3"}.fa-deafness:before,.fa-hard-of-hearing:before,.fa-deaf:before{content:"\f2a4"}.fa-glide:before{content:"\f2a5"}.fa-glide-g:before{content:"\f2a6"}.fa-signing:before,.fa-sign-language:before{content:"\f2a7"}.fa-low-vision:before{content:"\f2a8"}.fa-viadeo:before{content:"\f2a9"}.fa-viadeo-square:before{content:"\f2aa"}.fa-snapchat:before{content:"\f2ab"}.fa-snapchat-ghost:before{content:"\f2ac"}.fa-snapchat-square:before{content:"\f2ad"}.fa-pied-piper:before{content:"\f2ae"}.fa-first-order:before{content:"\f2b0"}.fa-yoast:before{content:"\f2b1"}.fa-themeisle:before{content:"\f2b2"}.fa-google-plus-circle:before,.fa-google-plus-official:before{content:"\f2b3"}.fa-fa:before,.fa-font-awesome:before{content:"\f2b4"}.fa-handshake-o:before{content:"\f2b5"}.fa-envelope-open:before{content:"\f2b6"}.fa-envelope-open-o:before{content:"\f2b7"}.fa-linode:before{content:"\f2b8"}.fa-address-book:before{content:"\f2b9"}.fa-address-book-o:before{content:"\f2ba"}.fa-vcard:before,.fa-address-card:before{content:"\f2bb"}.fa-vcard-o:before,.fa-address-card-o:before{content:"\f2bc"}.fa-user-circle:before{content:"\f2bd"}.fa-user-circle-o:before{content:"\f2be"}.fa-user-o:before{content:"\f2c0"}.fa-id-badge:before{content:"\f2c1"}.fa-drivers-license:before,.fa-id-card:before{content:"\f2c2"}.fa-drivers-license-o:before,.fa-id-card-o:before{content:"\f2c3"}.fa-quora:before{content:"\f2c4"}.fa-free-code-camp:before{content:"\f2c5"}.fa-telegram:before{content:"\f2c6"}.fa-thermometer-4:before,.fa-thermometer:before,.fa-thermometer-full:before{content:"\f2c7"}.fa-thermometer-3:before,.fa-thermometer-three-quarters:before{content:"\f2c8"}.fa-thermometer-2:before,.fa-thermometer-half:before{content:"\f2c9"}.fa-thermometer-1:before,.fa-thermometer-quarter:before{content:"\f2ca"}.fa-thermometer-0:before,.fa-thermometer-empty:before{content:"\f2cb"}.fa-shower:before{content:"\f2cc"}.fa-bathtub:before,.fa-s15:before,.fa-bath:before{content:"\f2cd"}.fa-podcast:before{content:"\f2ce"}.fa-window-maximize:before{content:"\f2d0"}.fa-window-minimize:before{content:"\f2d1"}.fa-window-restore:before{content:"\f2d2"}.fa-times-rectangle:before,.fa-window-close:before{content:"\f2d3"}.fa-times-rectangle-o:before,.fa-window-close-o:before{content:"\f2d4"}.fa-bandcamp:before{content:"\f2d5"}.fa-grav:before{content:"\f2d6"}.fa-etsy:before{content:"\f2d7"}.fa-imdb:before{content:"\f2d8"}.fa-ravelry:before{content:"\f2d9"}.fa-eercast:before{content:"\f2da"}.fa-microchip:before{content:"\f2db"}.fa-snowflake-o:before{content:"\f2dc"}.fa-superpowers:before{content:"\f2dd"}.fa-wpexplorer:before{content:"\f2de"}.fa-meetup:before{content:"\f2e0"}.sr-only{position:absolute;width:1px;height:1px;padding:0;margin:-1px;overflow:hidden;clip:rect(0, 0, 0, 0);border:0}.sr-only-focusable:active,.sr-only-focusable:focus{position:static;width:auto;height:auto;margin:0;overflow:visible;clip:auto} diff --git a/src/stylus/style.styl b/src/stylus/style.styl index 909fc71..e893336 100644 --- a/src/stylus/style.styl +++ b/src/stylus/style.styl @@ -94,6 +94,18 @@ tt .success background green +.fa.error + background inherit + color red + +.fa.warn + background inherit + color orange + +.fa.success + background inherit + color green + .load-on background-color #ccffcc color #000 @@ -511,10 +523,6 @@ span.unit position absolute color #fff - &.error - background-color inherit - color #ff3a3a - .path-viewer-messages margin 0.125em 0 @@ -528,7 +536,7 @@ span.unit background-color #333 background linear-gradient(to bottom, #666 0%, #222 100%); - &.small, &.error + &.small .path-viewer-content width 335px height 150px @@ -540,18 +548,6 @@ span.unit font-size 100% max-width 335px - &.error - .path-viewer-toolbar - display none - - .path-viewer-content - margin-top -2.5em - height 1.5em - background transparent - - .path-viewer-message - color red - .console .console-wrapper max-height 400px @@ -620,6 +616,17 @@ tr.log-debug td border 1px solid #ccc padding 1px + &.motor_fault + td, th + text-align center + min-width 1.75em + + .fa-eraser + cursor pointer + + &:hover + opacity 0.5 + .io &.active color green @@ -890,7 +897,7 @@ label.file-upload width 99% .path-viewer - &.small, &.error + &.small .path-viewer-content margin-top inherit float inherit