PKG_NAME := bbctrl-$(VERSION)
PUB_PATH := root@buildbotics.com:/var/www/buildbotics.com/bbctrl
+ifndef HOST
+HOST=bbctrl.local
+endif
+
ifndef DEST
DEST=mnt
endif
update: pkg
http_proxy= curl -i -X PUT -H "Content-Type: multipart/form-data" \
-F "firmware=@dist/$(PKG_NAME).tar.bz2" \
- http://bbctrl.local/api/firmware/update
+ http://$(HOST)/api/firmware/update
mount:
mkdir -p $(DEST)
- sshfs bbmc@bbctrl.local: $(DEST)
+ sshfs bbmc@$(HOST): $(DEST)
umount:
fusermount -u $(DEST)
init:
$(MAKE) erase
-$(MAKE) fuses
+ $(MAKE) fuses
$(MAKE) program-boot
$(MAKE) program
STALL_Y_PIN,
STALL_Z_PIN,
STALL_A_PIN,
- SPIN_DIR_PIN,
- SPIN_ENABLE_PIN,
+ TOOL_DIR_PIN,
+ TOOL_ENABLE_PIN,
ANALOG_PIN,
PROBE_PIN,
#define MOTORS 4 // number of motors on the board
#define COORDS 6 // number of supported coordinate systems
#define SWITCHES 10 // number of supported switches
-#define PWMS 2 // number of supported PWM channels
+#define OUTS 5 // number of supported pin outputs
// Switch settings. See switch.c
static void _init_clock() {
+#if 0 // 32Mhz Int RC
+ OSC.CTRL |= OSC_RC32MEN_bm | OSC_RC32KEN_bm; // Enable 32MHz & 32KHz osc
+ while (!(OSC.STATUS & OSC_RC32KRDY_bm)); // Wait for 32Khz oscillator
+ while (!(OSC.STATUS & OSC_RC32MRDY_bm)); // Wait for 32MHz oscillator
+
+ // Defaults to calibrate against internal 32Khz clock
+ DFLLRC32M.CTRL = DFLL_ENABLE_bm; // Enable DFLL
+ CCP = CCP_IOREG_gc; // Disable register security
+ CLK.CTRL = CLK_SCLKSEL_RC32M_gc; // Switch to 32MHz clock
+
+#else
// 12-16 MHz crystal; 0.4-16 MHz XTAL w/ 16K CLK startup
OSC.XOSCCTRL = OSC_FRQRANGE_12TO16_gc | OSC_XOSCSEL_XTAL_16KCLK_gc;
OSC.CTRL = OSC_XOSCEN_bm; // enable external crystal oscillator
CCP = CCP_IOREG_gc;
CLK.CTRL = CLK_SCLKSEL_PLL_gc; // switch to PLL clock
+#endif
OSC.CTRL &= ~OSC_RC2MEN_bm; // disable internal 2 MHz clock
}
#include "estop.h"
#include "i2c.h"
#include "pgmspace.h"
+#include "outputs.h"
#include "plan/planner.h"
#include "plan/arc.h"
cli(); // disable interrupts
hardware_init(); // hardware setup - must be first
+ outputs_init(); // output pins
usart_init(); // serial port
i2c_init(); // i2c port
drv8711_init(); // motor drivers
--- /dev/null
+/******************************************************************************\
+
+ This file is part of the Buildbotics firmware.
+
+ Copyright (c) 2015 - 2017 Buildbotics LLC
+ All rights reserved.
+
+ This file ("the software") is free software: you can redistribute it
+ and/or modify it under the terms of the GNU General Public License,
+ version 2 as published by the Free Software Foundation. You should
+ have received a copy of the GNU General Public License, version 2
+ along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+ The software is distributed in the hope that it will be useful, but
+ WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with the software. If not, see
+ <http://www.gnu.org/licenses/>.
+
+ For information regarding this software email:
+ "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#include "outputs.h"
+#include "config.h"
+
+
+typedef struct {
+ uint8_t pin;
+ bool active;
+ output_state_t state;
+ output_mode_t mode;
+} output_t;
+
+
+output_t outputs[OUTS] = {
+ {TOOL_ENABLE_PIN},
+ {TOOL_DIR_PIN},
+ {SWITCH_1_PIN},
+ {SWITCH_2_PIN},
+ {FAULT_PIN},
+};
+
+
+static output_t *_get_output(uint8_t pin) {
+ switch (pin) {
+ case TOOL_ENABLE_PIN: return &outputs[0];
+ case TOOL_DIR_PIN: return &outputs[1];
+ case SWITCH_1_PIN: return &outputs[2];
+ case SWITCH_2_PIN: return &outputs[3];
+ case FAULT_PIN: return &outputs[4];
+ }
+
+ return 0;
+}
+
+
+static void _update_state(output_t *output) {
+ switch (output->mode) {
+ case OUT_DISABLED: output->state = OUT_TRI; break;
+ case OUT_LO_HI: output->state = output->active ? OUT_HI : OUT_LO; break;
+ case OUT_HI_LO: output->state = output->active ? OUT_LO : OUT_HI; break;
+ case OUT_TRI_LO: output->state = output->active ? OUT_LO : OUT_TRI; break;
+ case OUT_TRI_HI: output->state = output->active ? OUT_HI : OUT_TRI; break;
+ case OUT_LO_TRI: output->state = output->active ? OUT_TRI : OUT_LO; break;
+ case OUT_HI_TRI: output->state = output->active ? OUT_TRI : OUT_HI; break;
+ }
+
+ switch (output->state) {
+ case OUT_TRI: DIRCLR_PIN(output->pin); break;
+ case OUT_HI: OUTSET_PIN(output->pin); DIRSET_PIN(output->pin); break;
+ case OUT_LO: OUTCLR_PIN(output->pin); DIRSET_PIN(output->pin); break;
+ }
+}
+
+
+void outputs_init() {
+ for (int i = 0; i < OUTS; i++) _update_state(&outputs[i]);
+}
+
+
+bool outputs_is_active(uint8_t pin) {
+ output_t *output = _get_output(pin);
+ return output ? output->active : false;
+}
+
+
+void outputs_set_active(uint8_t pin, bool active) {
+ output_t *output = _get_output(pin);
+ if (!output) return;
+
+ output->active = active;
+ _update_state(output);
+}
+
+
+void outputs_set_mode(uint8_t pin, output_mode_t mode) {
+ output_t *output = _get_output(pin);
+ if (!output) return;
+ output->mode = mode;
+}
+
+
+output_state_t outputs_get_state(uint8_t pin) {
+ output_t *output = _get_output(pin);
+ if (output) return OUT_TRI;
+ return output->state;
+}
+
+
+uint8_t get_output_state(uint8_t id) {
+ return OUTS <= id ? OUT_TRI : outputs[id].state;
+}
+
+
+uint8_t get_output_mode(uint8_t id) {
+ return OUTS <= id ? OUT_DISABLED : outputs[id].mode;
+}
+
+
+void set_output_mode(uint8_t id, uint8_t mode) {
+ if (OUTS <= id) return;
+ outputs[id].mode = mode;
+ _update_state(&outputs[id]);
+}
--- /dev/null
+/******************************************************************************\
+
+ This file is part of the Buildbotics firmware.
+
+ Copyright (c) 2015 - 2017 Buildbotics LLC
+ All rights reserved.
+
+ This file ("the software") is free software: you can redistribute it
+ and/or modify it under the terms of the GNU General Public License,
+ version 2 as published by the Free Software Foundation. You should
+ have received a copy of the GNU General Public License, version 2
+ along with the software. If not, see <http://www.gnu.org/licenses/>.
+
+ The software is distributed in the hope that it will be useful, but
+ WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
+ Lesser General Public License for more details.
+
+ You should have received a copy of the GNU Lesser General Public
+ License along with the software. If not, see
+ <http://www.gnu.org/licenses/>.
+
+ For information regarding this software email:
+ "Joseph Coffland" <joseph@buildbotics.com>
+
+\******************************************************************************/
+
+#pragma once
+
+#include <stdint.h>
+#include <stdbool.h>
+
+
+typedef enum {
+ OUT_LO,
+ OUT_HI,
+ OUT_TRI,
+} output_state_t;
+
+
+// OUT_inactive_active
+typedef enum {
+ OUT_DISABLED,
+ OUT_LO_HI,
+ OUT_HI_LO,
+ OUT_TRI_LO,
+ OUT_TRI_HI,
+ OUT_LO_TRI,
+ OUT_HI_TRI,
+} output_mode_t;
+
+
+void outputs_init();
+bool outputs_is_active(uint8_t pin);
+void outputs_set_active(uint8_t pin, bool active);
+void outputs_set_mode(uint8_t pin, output_mode_t mode);
+output_state_t outputs_get_state(uint8_t pin);
}
+#if 0
+static float _axis_velocity_at_limits(int axis) {
+ float V = jr.axes[axis].velocity;
+
+ if (axis_get_homed(axis)) {
+ float min = axis_get_travel_min(axis);
+ float max = axis_get_travel_max(axis);
+
+ if (position <= min) return 0;
+ if (max <= position) return 0;
+
+ float position = mp_runtime_get_axis_position(axis);
+ float jerk = axis_get_jerk_max(axis) * JERK_MULTIPLIER;
+ float decelDist = mp_get_target_length(V, 0, jerk * JOG_JERK_MULT);
+
+ if (position < min + decelDist) {
+ }
+
+ if (max - decelDist < position) {
+ }
+ }
+
+ return V;
+}
+#endif
+
+
static stat_t _exec_jog(mp_buffer_t *bf) {
// Load next velocity
jr.done = true;
mp_buffer_t *prev = mp_buffer_prev(bf);
while (prev->state != BUFFER_OFF)
if (prev->flags & BUFFER_LINE) {
- _get_junction_vmax(prev->unit, bf->unit);
+ junction_velocity = _get_junction_vmax(prev->unit, bf->unit);
break;
} else prev = mp_buffer_prev(prev);
// Zero out exact stop cases
if (exact_stop) bf->entry_vmax = bf->exit_vmax = 0;
- else bf->flags |= BUFFER_REPLANNABLE;
}
*/
stat_t mp_aline(const float target[], buffer_flags_t flags, switch_id_t sw,
float feed_rate, float feed_override, int32_t line) {
- DEBUG_CALL("(%f, %f, %f, %f), %s, %s, %s, %f, %f, %d", target[0], target[1],
- target[2], target[3],
- (flags & BUFFER_RAPID) ? "true" : "false",
- (flags & BUFFER_INVERSE_TIME) ? "true" : "false",
- (flags & BUFFER_EXACT_STOP) ? "true" : "false",
+ DEBUG_CALL("(%f, %f, %f, %f), %s%s%s, %f, %f, %d",
+ target[0], target[1], target[2], target[3],
+ (flags & BUFFER_RAPID) ? "rapid|" : "",
+ (flags & BUFFER_INVERSE_TIME) ? "inverse_time|" : "",
+ (flags & BUFFER_EXACT_STOP) ? "exact_stop|" : "",
feed_rate, feed_override, line);
// Trap zero feed rate condition
feed_override);
_calc_max_velocities(bf, time, flags & BUFFER_EXACT_STOP);
- // Note, the following lines must remain in order.
- bf->line = line; // Planner needs this when planning steps
flags |= BUFFER_LINE;
- bf->flags = flags; // Move flags
- bf->sw = sw; // Seek switche
- mp_plan(bf); // Plan block list
- mp_set_position(target); // Set planner position before committing buffer
+ if (!(flags & BUFFER_EXACT_STOP)) flags |= BUFFER_REPLANNABLE;
+
+ // Note, the following lines must remain in order.
+ bf->line = line; // Planner needs this when planning steps
+ bf->flags = flags; // Move flags
+ bf->sw = sw; // Seek switch, if any
+ mp_plan(bf); // Plan block list
+ mp_set_position(target); // Set planner position before pushing buffer
mp_queue_push(mp_exec_aline, line); // After position update
return STAT_OK;
#if 0
+void mp_print_buffer(mp_buffer_t *bp) {
+ printf_P(PSTR("{\"msg\":\"%d,0x%04lx,"
+ "%0.2f,%0.2f,%0.2f,%0.2f,"
+ "%0.2f,%0.2f,%0.2f,%0.2f,"
+ "%0.2f,%0.2f,%0.2f\"}\n"),
+ bp->flags & BUFFER_REPLANNABLE, (intptr_t)bp->cb,
+ bp->length, bp->head_length, bp->body_length, bp->tail_length,
+ bp->entry_velocity, bp->cruise_velocity, bp->exit_velocity,
+ bp->braking_velocity,
+ bp->entry_vmax, bp->cruise_vmax, bp->exit_vmax);
+
+ while (!usart_tx_empty()) continue;
+}
+
+
/// Prints the entire planning queue as comma separated values embedded in
/// JSON ``msg`` entries. Used for debugging.
void mp_print_queue(mp_buffer_t *bf) {
- printf_P(PSTR("{\"msg\":\"id,replannable,callback,"
+ printf_P(PSTR("{\"msg\":\"replannable,callback,"
"length,head_length,body_length,tail_length,"
"entry_velocity,cruise_velocity,exit_velocity,braking_velocity,"
"entry_vmax,cruise_vmax,exit_vmax\"}\n"));
- int i = 0;
mp_buffer_t *bp = bf;
while (bp) {
- printf_P(PSTR("{\"msg\":\"%d,%d,0x%04lx,"
- "%0.2f,%0.2f,%0.2f,%0.2f,"
- "%0.2f,%0.2f,%0.2f,%0.2f,"
- "%0.2f,%0.2f,%0.2f\"}\n"),
- i++, bp->flags & BUFFER_REPLANNABLE, (intptr_t)bp->cb,
- bp->length, bp->head_length, bp->body_length, bp->tail_length,
- bp->entry_velocity, bp->cruise_velocity, bp->exit_velocity,
- bp->braking_velocity,
- bp->entry_vmax, bp->cruise_vmax, bp->exit_vmax);
-
+ mp_print_buffer(bp);
bp = mp_buffer_prev(bp);
if (bp == bf || bp->state == BUFFER_OFF) break;
}
-
- while (!usart_tx_empty()) continue;
}
#endif
* list can be recomputed regardless of exact stops and previous replanning
* optimizations.
*/
-void mp_plan(mp_buffer_t *bl) {
- mp_buffer_t *bp = bl;
+void mp_plan(mp_buffer_t *bf) {
+ mp_buffer_t *bp = bf;
// Backward planning pass. Find first block and update braking velocities.
// By the end bp points to the buffer before the first block.
mp_buffer_t *next = bp;
- while ((bp = mp_buffer_prev(bp)) != bl) {
+ while ((bp = mp_buffer_prev(bp)) != bf) {
if (!(bp->flags & BUFFER_REPLANNABLE)) break;
+ // TODO what about non-move buffers?
bp->braking_velocity =
min(next->entry_vmax, next->braking_velocity) + bp->delta_vmax;
next = bp;
}
- // Forward planning pass. Recompute trapezoids from the first block to bl.
+ // Forward planning pass. Recompute trapezoids from the first block to bf.
mp_buffer_t *prev = bp;
- while ((bp = mp_buffer_next(bp)) != bl) {
+ while ((bp = mp_buffer_next(bp)) != bf) {
mp_buffer_t *next = mp_buffer_next(bp);
- bp->entry_velocity = prev == bl ? bp->entry_vmax : prev->exit_velocity;
+ bp->entry_velocity = prev == bf ? bp->entry_vmax : prev->exit_velocity;
bp->cruise_velocity = bp->cruise_vmax;
bp->exit_velocity = min4(bp->exit_vmax, next->entry_vmax,
next->braking_velocity,
}
// Finish last block
- bl->entry_velocity = prev->exit_velocity;
- bl->cruise_velocity = bl->cruise_vmax;
- bl->exit_velocity = 0;
+ bf->entry_velocity = prev->exit_velocity;
+ bf->cruise_velocity = bf->cruise_vmax;
+ bf->exit_velocity = 0;
- mp_calculate_trapezoid(bl);
+ mp_calculate_trapezoid(bf);
}
#include "config.h"
#include "estop.h"
+#include "outputs.h"
typedef struct {
float max_rpm;
float min_duty;
float max_duty;
- bool reverse;
- bool enable_invert;
bool pwm_invert;
} pwm_spindle_t;
static pwm_spindle_t spindle = {0};
-static void _spindle_set_enable(bool enable) {
- SET_PIN(SPIN_ENABLE_PIN, enable ^ spindle.enable_invert);
+static void _set_enable(bool enable) {
+ outputs_set_active(TOOL_ENABLE_PIN, enable);
}
-static void _spindle_set_dir(bool forward) {
- SET_PIN(SPIN_DIR_PIN, !(forward ^ spindle.reverse));
+static void _set_dir(bool clockwise) {
+ outputs_set_active(TOOL_DIR_PIN, !clockwise);
}
-static void _spindle_set_pwm(spindle_mode_t mode, float speed) {
+static void _set_pwm(spindle_mode_t mode, float speed) {
if (mode == SPINDLE_OFF || speed < spindle.min_rpm || estop_triggered()) {
TIMER_PWM.CTRLA = 0;
OUTCLR_PIN(SPIN_PWM_PIN);
- _spindle_set_enable(false);
+ _set_enable(false);
return;
}
void pwm_spindle_init() {
// Configure IO
- _spindle_set_dir(true);
- _spindle_set_enable(false);
+ _set_dir(true);
+ _set_enable(false);
DIRSET_PIN(SPIN_PWM_PIN); // Output
- DIRSET_PIN(SPIN_DIR_PIN); // Output
- DIRSET_PIN(SPIN_ENABLE_PIN); // Output
}
void pwm_spindle_set(spindle_mode_t mode, float speed) {
- _spindle_set_dir(mode == SPINDLE_CW);
- _spindle_set_pwm(mode, speed);
- _spindle_set_enable(mode != SPINDLE_OFF && TIMER_PWM.CTRLA);
+ if (mode != SPINDLE_OFF) _set_dir(mode == SPINDLE_CW);
+ _set_pwm(mode, speed);
+ _set_enable(mode != SPINDLE_OFF);
}
-void pwm_spindle_stop() {_spindle_set_pwm(SPINDLE_OFF, 0);}
+void pwm_spindle_stop() {pwm_spindle_set(SPINDLE_OFF, 0);}
// TODO these need more effort and should work with the huanyang spindle too
void set_spin_min_duty(float value) {spindle.min_duty = value / 100;}
float get_spin_max_duty() {return spindle.max_duty * 100;}
void set_spin_max_duty(float value) {spindle.max_duty = value / 100;}
-uint8_t get_spin_reverse() {return spindle.reverse;}
-void set_spin_reverse(uint8_t value) {spindle.reverse = value;}
float get_spin_up() {return 0;} // TODO
void set_spin_up(float value) {} // TODO
float get_spin_down() {return 0;} // TODO
void set_spin_down(float value) {} // TODO
uint16_t get_spin_freq() {return spindle.freq;}
void set_spin_freq(uint16_t value) {spindle.freq = value;}
-bool get_enable_invert() {return spindle.enable_invert;}
-void set_enable_invert(bool value) {spindle.enable_invert = value;}
bool get_pwm_invert() {return spindle.pwm_invert;}
void set_pwm_invert(bool value) {spindle.pwm_invert = value;}
spindle_type_t type;
spindle_mode_t mode;
float speed;
+ bool reversed;
} spindle_t;
void _spindle_set(spindle_mode_t mode, float speed) {
- spindle.mode = mode;
- spindle.speed = speed;
-
- switch (spindle.type) {
- case SPINDLE_TYPE_PWM: pwm_spindle_set(mode, speed); break;
- case SPINDLE_TYPE_HUANYANG: huanyang_set(mode, speed); break;
- }
-}
-
+ if (speed < 0) speed = 0;
+ if (mode != SPINDLE_CW && mode != SPINDLE_CCW) mode = SPINDLE_OFF;
-void spindle_set_mode(spindle_mode_t mode) {
spindle.mode = mode;
+ spindle.speed = speed;
- switch (spindle.type) {
- case SPINDLE_TYPE_PWM: pwm_spindle_set(mode, spindle.speed); break;
- case SPINDLE_TYPE_HUANYANG: huanyang_set(mode, spindle.speed); break;
+ if (spindle.reversed) {
+ if (mode == SPINDLE_CW) mode = SPINDLE_CCW;
+ else if (mode == SPINDLE_CCW) mode = SPINDLE_CW;
}
-}
-
-
-void spindle_set_speed(float speed) {
- if (speed < 0) speed = 0;
- spindle.speed = speed;
switch (spindle.type) {
- case SPINDLE_TYPE_PWM: pwm_spindle_set(spindle.mode, speed); break;
- case SPINDLE_TYPE_HUANYANG: huanyang_set(spindle.mode, speed); break;
+ case SPINDLE_TYPE_PWM: pwm_spindle_set(mode, speed); break;
+ case SPINDLE_TYPE_HUANYANG: huanyang_set(mode, speed); break;
}
}
+void spindle_set_mode(spindle_mode_t mode) {_spindle_set(mode, spindle.speed);}
+void spindle_set_speed(float speed) {_spindle_set(spindle.mode, speed);}
spindle_mode_t spindle_get_mode() {return spindle.mode;}
float spindle_get_speed() {return spindle.speed;}
_spindle_set(mode, speed);
}
}
+
+
+bool spindle_is_reversed() {return spindle.reversed;}
+bool get_spin_reversed() {return spindle.reversed;}
+
+
+void set_spin_reversed(bool reversed) {
+ spindle.reversed = reversed;
+ _spindle_set(spindle.mode, spindle.speed);
+}
+
+
+PGM_P get_spin_mode() {
+ switch (spindle.mode) {
+ case SPINDLE_CW: return PSTR("Clockwise");
+ case SPINDLE_CCW: return PSTR("Counterclockwise");
+ default: break;
+ }
+ return PSTR("Off");
+}
spindle_mode_t spindle_get_mode();
float spindle_get_speed();
void spindle_stop();
+bool spindle_is_reversed();
}
-bool switch_is_active(int index) {
- return switches[index].state;
-}
+bool switch_is_active(int index) {return switches[index].state;}
bool switch_is_enabled(int index) {
uint8_t get_probe_mode() {return switch_get_type(SW_PROBE);}
void set_probe_mode(uint8_t value) {switch_set_type(SW_PROBE, value);}
-bool get_min_switch(int index) {return switch_is_active(MIN_SWITCH(index));}
-bool get_max_switch(int index) {return switch_is_active(MAX_SWITCH(index));}
-bool get_estop_switch() {return switch_is_active(SW_ESTOP);}
-bool get_probe_switch() {return switch_is_active(SW_PROBE);}
+
+static uint8_t _get_state(int index) {
+ if (!switch_is_enabled(index)) return 2; // Disabled
+ return switch_is_active(index);
+}
+
+
+uint8_t get_min_switch(int index) {return _get_state(MIN_SWITCH(index));}
+uint8_t get_max_switch(int index) {return _get_state(MAX_SWITCH(index));}
+uint8_t get_estop_switch() {return _get_state(SW_ESTOP);}
+uint8_t get_probe_switch() {return _get_state(SW_PROBE);}
This file is part of the Buildbotics firmware.
Copyright (c) 2015 - 2017 Buildbotics LLC
- Copyright (c) 2010 - 2015 Alden S. Hart, Jr.
All rights reserved.
This file ("the software") is free software: you can redistribute it
#define AXES_LABEL "xyzabcuvw"
#define MOTORS_LABEL "0123"
+#define OUTS_LABEL "ed12f"
// VAR(name, code, type, index, settable, report, help)
VAR(max_sw_mode, xs, uint8_t, MOTORS, 1, 1, "Maximum switch mode")
VAR(estop_mode, et, uint8_t, 0, 1, 1, "Estop switch mode")
VAR(probe_mode, pt, uint8_t, 0, 1, 1, "Probe switch mode")
-
-VAR(min_switch, lw, bool, MOTORS, 0, 1, "Minimum switch state")
-VAR(max_switch, xw, bool, MOTORS, 0, 1, "Maximum switch state")
-VAR(estop_switch, ew, bool, 0, 0, 1, "Estop switch state")
-VAR(probe_switch, pw, bool, 0, 0, 1, "Probe switch state")
+VAR(min_switch, lw, uint8_t, MOTORS, 0, 1, "Minimum switch state")
+VAR(max_switch, xw, uint8_t, MOTORS, 0, 1, "Maximum switch state")
+VAR(estop_switch, ew, uint8_t, 0, 0, 1, "Estop switch state")
+VAR(probe_switch, pw, uint8_t, 0, 0, 1, "Probe switch state")
// Homing
VAR(homing_mode, ho, uint8_t, MOTORS, 1, 1, "Homing type")
VAR(axis_work_coord, w, float, AXES, 0, 1, "Axis work coordinate")
VAR(axis_can_home, ch, bool, AXES, 0, 1, "Is axis configured for homing")
+// Outputs
+VAR(output_state, os, uint8_t, OUTS, 0, 1, "Output pin state")
+VAR(output_mode, om, uint8_t, OUTS, 1, 1, "Output pin mode")
+
// Spindle
VAR(spindle_type, st, uint8_t, 0, 1, 1, "PWM=0 or HUANYANG=1")
-VAR(spin_reverse, sr, bool, 0, 1, 1, "Reverse spin")
+VAR(spin_reversed, sr, bool, 0, 1, 1, "Reverse spin")
VAR(max_spin, sx, float, 0, 1, 1, "Maximum spindle speed")
VAR(min_spin, sm, float, 0, 1, 1, "Minimum spindle speed")
VAR(spin_min_duty, nd, float, 0, 1, 1, "Minimum PWM duty cycle")
VAR(spin_up, su, float, 0, 1, 1, "Spin up velocity")
VAR(spin_down, sd, float, 0, 1, 1, "Spin down velocity")
VAR(spin_freq, sf, uint16_t, 0, 1, 1, "Spindle PWM frequency")
+VAR(spin_mode, ss, pstring, 0, 0, 1, "Spindle mode")
// PWM spindle
VAR(pwm_invert, pi, bool, 0, 1, 1, "Inverted spindle PWM")
-VAR(enable_invert, ei, bool, 0, 1, 1, "Inverted spindle enable")
// Huanyang spindle
VAR(huanyang_id, hi, uint8_t, 0, 1, 1, "Huanyang ID")
{
"name": "bbctrl",
- "version": "0.1.12",
+ "version": "0.1.18",
"homepage": "https://github.com/buildbotics/rpi-firmware",
"license": "GPL 3+",
./setup.py install --force
service bbctrl start
fi
+
+sync
--- /dev/null
+#!/bin/bash -e
+
+HOSTNAME="$1"
+
+if [ "$HOSTNAME" == "" ]; then
+ echo "Usage: $0 <hostname>"
+ exit 1
+fi
+
+if [ $(echo "$HOSTNAME" | tr '[:upper:]' '[:lower:]') == "localhost" ]; then
+ echo "Cannot set hostname to 'localhost'"
+ exit 1
+fi
+
+if [[ ! "$HOSTNAME" =~ ^[a-zA-Z0-9-]{1,63}$ ]]; then
+ echo "Invalid hostname '$HOSTNAME'"
+ exit 1
+fi
+
+sed -i "s/^127.0.1.1\([[:space:]]*\).*$/127.0.1.1\1$HOSTNAME/" /etc/hosts
+echo "$HOSTNAME" > /etc/hostname
+/etc/init.d/hostname.sh
+sync
td RPM
tr
th Direction
- td {{state.sd || 'Clockwise'}}
+ td {{state.ss || 'Off'}}
td
table.info
label(for="tab4") Console
input#tab5(type="radio", name="tabs")
- label(for="tab5") Video
+ label(for="tab5") Indicators
+
+ input#tab6(type="radio", name="tabs", @click="load_video")
+ label(for="tab6") Video
section#content1.tab-content
.toolbar
td {{msg.msg}}
section#content5.tab-content
+ component(is="indicators", :state="state")
+
+ section#content6.tab-content
.video
- img.mjpeg(src="http://bbctrl.local:8000/stream/0")
+ img.mjpeg(:src="video_url")
--- /dev/null
+script#indicators-template(type="text/x-template")
+ .indicators
+ table
+ tr
+ th(colspan=4) Switch Inputs
+
+ each motor in '01234'
+ tr(v-if="is_motor_enabled(#{motor})")
+ td
+ .fa(:class="get_class('#{motor}lw')")
+ th #{motor} Min
+
+ td
+ .fa(:class="get_class('#{motor}xw')")
+ th #{motor} Max
+
+ tr
+ td
+ .fa(:class="get_class('ew')")
+ th Estop
+
+ td
+ .fa(:class="get_class('pw')")
+ th Probe
+
+ table
+ tr
+ th(colspan=4) Outputs
+
+ tr
+ td
+ .fa(:class="get_class('eos')")
+ th Tool Enable
+
+ td
+ .fa(:class="get_class('dos')")
+ th Tool Direction
+
+ tr
+ td
+ .fa(:class="get_class('1os')")
+ th Load 1
+
+ td
+ .fa(:class="get_class('2os')")
+ th Load 2
+
+ tr
+ td
+ .fa(:class="get_class('fos')")
+ th(colspan=3) Fault
+
+ table
+ tr
+ th(colspan=4) Measurements
+
+ tr
+ td {{state['vin'] | fixed 1}} V
+ th Input
+
+ td {{state['vout'] | fixed 1}} V
+ th Output
+
+ tr
+ td {{state['motor'] | fixed 2}} A
+ th Motor
+
+ td {{state['temp'] | fixed 0}} ℃
+ th Temp
+
+ tr
+ td {{state['load1'] | fixed 2}} A
+ th Load 1
+
+ td {{state['load2'] | fixed 2}} A
+ th Load 2
+
+ table
+ tr
+ th(colspan=4) RS485 Spindle
+
+ tr
+ th(colspan=4) {{state['he'] ? "" : "Not "}}Connected
+
+ tr
+ td {{state['hz']}} Hz
+ th Frequency
+
+ td {{state['hc']}} A
+ th Current
+
+ tr
+ td {{state['hr']}} RPM
+ th Speed
+
+ td {{state['ht']}} ℃
+ th Temp
+
+ table
+ tr
+ th(colspan=10) Legend
+
+ tr
+ td
+ .fa.fa-circle.logic-hi
+ th Logic Hi
+
+ td
+ .fa.fa-circle.logic-lo
+ th Logic Lo
+
+ td
+ .fa.fa-circle-o.logic-tri
+ th Tristated
manual_home: {x: false, y: false, z: false, a: false, b: false, c: false},
position_msg:
{x: false, y: false, z: false, a: false, b: false, c: false},
- axis_position: 0
+ axis_position: 0,
+ video_url: ''
}
},
},
- clear_console: function () {this.console = [];}
- },
-
+ clear_console: function () {this.console = [];},
- filters: {
- percent: function (value, precision) {
- if (typeof precision == 'undefined') precision = 2;
- return (value * 100.0).toFixed(precision) + '%';
- },
-
- fixed: function (value, precision) {return value.toFixed(precision)},
- upper: function (value) {return value.toUpperCase()}
+ load_video: function () {
+ this.video_url = '//' + document.location.hostname + ':8000/stream/0';
+ }
}
}
--- /dev/null
+'use strict'
+
+
+module.exports = {
+ template: '#indicators-template',
+ props: ['state'],
+
+
+ methods: {
+ is_motor_enabled: function (motor) {
+ return typeof this.state[motor + 'pm'] != 'undefined' &&
+ this.state[motor + 'pm'];
+ },
+
+
+ get_class: function (code) {
+ if (typeof this.state[code] != 'undefined') {
+ var state = this.state[code];
+
+ if (state == 0 || state === false) return 'logic-lo fa-circle';
+ if (state == 1 || state === true) return 'logic-hi fa-circle';
+ if (state == 2) return 'logic-tri fa-circle-o';
+ }
+
+ return 'fa-exclamation-triangle warn';
+ }
+ }
+}
// Register global components
Vue.component('templated-input', require('./templated-input'));
Vue.component('message', require('./message'));
+ Vue.component('indicators', require('./indicators'));
+
+ Vue.filter('percent', function (value, precision) {
+ if (typeof precision == 'undefined') precision = 2;
+ return (value * 100.0).toFixed(precision) + '%';
+ });
+
+ Vue.filter('fixed', function (value, precision) {
+ if (typeof value == 'undefined') return '';
+ return value.toFixed(precision)
+ });
+
+ Vue.filter('upper', function (value) {
+ if (typeof value == 'undefined') return '';
+ return value.toUpperCase()
+ });
// Vue app
require('./app');
GATE_DDR = (1 << GATE1_PIN) | (1 << 2);
GATE_PORT = (1 << GATE1_PIN) | (1 << 2);
- while (true) continue;
-
// Start ADC
adc_conversion();
log.error('Updating Web: %s', e)
+ def _find_motor(self, axis):
+ for motor in range(6):
+ if not ('%dan' % motor) in self.vars: continue
+ motor_axis = 'xyzabc'[self.vars['%dan' % motor]]
+ if motor_axis == axis.lower() and self.vars['%dpm' % motor]:
+ return motor
+
+
def _update_lcd(self, msg):
if 'x' in msg or 'c' in msg:
v = self.vars
self.lcd_page.text('%-9s' % state, 0, 0)
- if 'xp' in msg: self.lcd_page.text('% 10.3fX' % msg['xp'], 9, 0)
- if 'yp' in msg: self.lcd_page.text('% 10.3fY' % msg['yp'], 9, 1)
- if 'zp' in msg: self.lcd_page.text('% 10.3fZ' % msg['zp'], 9, 2)
- if 'ap' in msg: self.lcd_page.text('% 10.3fA' % msg['ap'], 9, 3)
+ # Show enabled axes
+ row = 0
+ for axis in 'xyzabc':
+ motor = self._find_motor(axis)
+ if motor is not None:
+ if (axis + 'p') in msg:
+ self.lcd_page.text('% 10.3f%s' % (
+ msg[axis + 'p'], axis.upper()), 9, row)
+
+ row += 1
+
if 't' in msg: self.lcd_page.text('%2uT' % msg['t'], 6, 1)
if 'u' in msg: self.lcd_page.text('%-6s' % msg['u'], 0, 1)
if 'f' in msg: self.lcd_page.text('%8uF' % msg['f'], 0, 2)
import json
import logging
import pkg_resources
+import subprocess
import bbctrl
with open('config.json', 'w') as f:
json.dump(config, f)
+ subprocess.check_call(['sync'])
+
log.info('Saved')
def __init__(self, ctrl):
self.ctrl = ctrl
+ self.addrs = self.ctrl.args.lcd_addr
+ self.addr = self.addrs[0]
+ self.addr_num = 0
+
self.width = 20
self.height = 4
self.lcd = None
try:
if self.lcd is None:
- self.lcd = lcd.LCD(self.ctrl.i2c, self.ctrl.args.lcd_addr,
- self.height, self.width)
+ self.lcd = lcd.LCD(self.ctrl.i2c, self.addr, self.height,
+ self.width)
if self.reset:
self.lcd.reset()
self.redraw = False
except IOError as e:
- log.error('LCD communication failed, retrying: %s' % e)
+ # Try next address
+ self.addr_num += 1
+ if len(self.addrs) <= self.addr_num: self.addr_num = 0
+ self.addr = self.addrs[self.addr_num]
+ self.lcd = None
+
+ log.error('LCD communication failed, ' +
+ 'retrying on address 0x%02x: %s' % (self.addr, e))
+
self.reset = True
self.timeout = self.ctrl.ioloop.call_later(1, self._update)
self.ctrl = ctrl
self.i2c_addr = ctrl.args.pwr_addr
- self.regs = [0] * 6
+ self.regs = [-1] * 6
self.lcd_page = ctrl.lcd.add_new_page()
self._update()
def _update(self):
+ update = {}
+
try:
for i in range(len(self.regs)):
value = self.ctrl.i2c.read_word(self.i2c_addr + i)
- if i == TEMP_REG: self.regs[TEMP_REG] = value - 273
- else: self.regs[i] = value / 100.0
+ if i == TEMP_REG: value -= 273
+ else: value /= 100.0
+
+ if self.regs[i] != value:
+ key = ['temp', 'vin', 'vout', 'motor', 'load1', 'load2'][i]
+ update[key] = value
+ self.regs[i] = value
except Exception as e:
log.warning('Pwr communication failed: %s' % e)
self.lcd_page.text('%5.1fA Ld1' % self.regs[LOAD1_REG], 10, 1)
self.lcd_page.text('%5.1fA Ld2' % self.regs[LOAD2_REG], 10, 2)
+ if len(update): self.ctrl.web.broadcast(update)
+
self.ctrl.ioloop.call_later(0.25, self._update)
help = 'Serial baud rate')
parser.add_argument('--i2c-port', default = 1, type = int,
help = 'I2C port')
- parser.add_argument('--lcd-addr', default = 0x27, type = int,
+ parser.add_argument('--lcd-addr', default = [0x27, 0x3f], type = int,
help = 'LCD I2C address')
parser.add_argument('--avr-addr', default = 0x2b, type = int,
help = 'AVR I2C address')
"homing": {
"homing-mode": {
"type": "enum",
- "values": [
- "manual", "stall-min", "stall-max", "switch-min", "switch-max"
- ],
+ "values": ["manual", "switch-min", "switch-max"],
"default": "manual",
"code": "ho"
},
"default": "false",
"code": "pi"
},
- "enable-inverted": {
- "type": "bool",
- "default": "false",
- "code": "ei"
+ "tool-enable-mode": {
+ "type": "enum",
+ "values": ["disabled", "lo-hi", "hi-lo", "tri-lo", "tri-hi", "lo-tri",
+ "hi-tri"],
+ "default": "lo-hi",
+ "code": "eom"
+ },
+ "tool-direction-mode": {
+ "type": "enum",
+ "values": ["disabled", "lo-hi", "hi-lo", "tri-lo", "tri-hi", "lo-tri",
+ "hi-tri"],
+ "default": "lo-hi",
+ "code": "dom"
}
},
&.debug td
color green
+ .indicators
+ table
+ display inline-block
+ vertical-align top
+ margin 0.5em
+ empty-cells show
+
+ td, th
+ padding 4px
+
+ .logic-lo
+ color black
+
+ .logic-hi
+ color green
+
+ .warn
+ background-color transparent
+ color orange
+
+ .video
+ text-align center
+ line-height 0
+
.tabs
clear both
> label
display block
float left
- width 5em
+ width 6em
font-weight bold
cursor pointer
text-decoration none
> #tab2:checked ~ #content2,
> #tab3:checked ~ #content3,
> #tab4:checked ~ #content4,
- > #tab5:checked ~ #content5
+ > #tab5:checked ~ #content5,
+ > #tab6:checked ~ #content6,
+ > #tab7:checked ~ #content7,
+ > #tab8:checked ~ #content8,
+ > #tab9:checked ~ #content9
display block
[id^="tab"]:checked + label