Browse Source

bunch of work on firmware

Thomas Buck 3 years ago
parent
commit
f36252bde3
9 changed files with 590 additions and 24 deletions
  1. 37
    8
      include/config.h
  2. 44
    0
      include/config_pins.h
  3. 29
    0
      include/data.h
  4. 26
    0
      include/statemachine.h
  5. 164
    0
      src/data.cpp
  6. 4
    0
      src/main.cpp
  7. 35
    0
      src/statemachine.cpp
  8. 21
    0
      src/states.cpp
  9. 230
    16
      src/steppers.cpp

+ 37
- 8
include/config.h View File

@@ -20,29 +20,25 @@
20 20
 #define USE_20X4_TEXT_LCD
21 21
 //#define USE_FULL_GRAPHIC_LCD
22 22
 
23
+// xy steps per mm
23 24
 #define XY_BELT_PITCH 2.0
24 25
 #define XY_PULLEY_TEETH 40.0
25 26
 #define XY_MICRO_STEPS 16.0
26 27
 #define XY_MOTOR_STEPS_PER_REV (200.0 * XY_MICRO_STEPS)
27 28
 #define XY_STEPS_PER_MM (XY_MOTOR_STEPS_PER_REV / XY_PULLEY_TEETH / XY_BELT_PITCH)
28 29
 
30
+// z steps per mm
29 31
 #define Z_ROD_PITCH 2.0
30 32
 #define Z_MICRO_STEPS 16.0
31 33
 #define Z_MOTOR_STEPS_PER_REV (200.0 * Z_MICRO_STEPS)
32 34
 #define Z_STEPS_PER_MM (Z_MOTOR_STEPS_PER_REV / Z_ROD_PITCH)
33 35
 
36
+// e steps per mm
34 37
 #define E_MICRO_STEPS 16.0
35 38
 #define E_MOTOR_STEPS_PER_REV (200.0 * E_MICRO_STEPS)
36 39
 #define E_STEPS_PER_MM (E_MOTOR_STEPS_PER_REV / 42) // TODO
37 40
 
38
-#define XY_MAX_SPEED 50.0 // in mm/s
39
-#define Z_MAX_SPEED 20.0 // in mm/s
40
-#define E_MAX_SPEED 10.0 // in mm/s
41
-
42
-#define XY_MAX_ACCEL 100.0 // in mm/s^2
43
-#define Z_MAX_ACCEL 50.0 // in mm/s^2
44
-#define E_MAX_ACCEL 20.0 // in mm/s^2
45
-
41
+// travel lengths
46 42
 #define X_AXIS_MIN -5.0 // in mm
47 43
 #define X_AXIS_MAX 260.0 // in mm
48 44
 #define Y_AXIS_MIN -5.0 // in mm
@@ -52,4 +48,37 @@
52 48
 #define E_AXIS_MIN 0.0 // in mm
53 49
 #define E_AXIS_MAX 6.0 // in mm
54 50
 
51
+// maximum speeds
52
+#define XY_MAX_SPEED 50.0 // in mm/s
53
+#define Z_MAX_SPEED 20.0 // in mm/s
54
+#define E_MAX_SPEED 10.0 // in mm/s
55
+
56
+// homing speeds
57
+#define XY_FAST_HOME_SPEED 2.5 // in mm/s
58
+#define XY_SLOW_HOME_SPEED 1.0 // in mm/s
59
+#define Z_FAST_HOME_SPEED 2.0 // in mm/s
60
+#define Z_SLOW_HOME_SPEED 1.0 // in mm/s
61
+#define E_FAST_HOME_SPEED 0.1 // in mm/s
62
+#define E_SLOW_HOME_SPEED 0.05 // in mm/s
63
+
64
+// accelerations
65
+#define XY_MAX_ACCEL 100.0 // in mm/s^2
66
+#define Z_MAX_ACCEL 50.0 // in mm/s^2
67
+#define E_MAX_ACCEL 20.0 // in mm/s^2
68
+
69
+// axis movement directions (1.0 normal, -1.0 inverted)
70
+#define X_AXIS_MOVEMENT_DIR 1.0
71
+#define Y_AXIS_MOVEMENT_DIR 1.0
72
+#define Z_AXIS_MOVEMENT_DIR 1.0
73
+#define E_AXIS_MOVEMENT_DIR 1.0
74
+
75
+// homing back-off
76
+#define XY_BACK_OFF_DISTANCE 10.0 // in mm
77
+#define Z_BACK_OFF_DISTANCE 5.0 // in mm
78
+#define E_BACK_OFF_DISTANCE 2.0 // in mm
79
+
80
+#define XY_HOME_BACK_OFF_TIME (XY_BACK_OFF_DISTANCE / XY_FAST_HOME_SPEED * 1000)
81
+#define Z_HOME_BACK_OFF_TIME (Z_BACK_OFF_DISTANCE / Z_FAST_HOME_SPEED * 1000)
82
+#define E_HOME_BACK_OFF_TIME (E_BACK_OFF_DISTANCE / E_FAST_HOME_SPEED * 1000)
83
+
55 84
 #endif // _CONFIG_H_

+ 44
- 0
include/config_pins.h View File

@@ -27,6 +27,10 @@
27 27
 #define E0_DIR_PIN         28
28 28
 #define E0_ENABLE_PIN      24
29 29
 
30
+// use the remaining z endstop pin for e axis
31
+#define E_MIN_PIN          18
32
+#define E_MAX_PIN          -1
33
+
30 34
 //extruder 2
31 35
 #define E1_STEP_PIN        36
32 36
 #define E1_DIR_PIN         34
@@ -90,3 +94,43 @@
90 94
 #if ((Y_MIN_PIN != -1) && (Y_MAX_PIN != -1)) || ((Y_MIN_PIN == -1) && (Y_MAX_PIN == -1))
91 95
 #error define one of Y_MIN_PIN or Y_MAX_PIN
92 96
 #endif
97
+
98
+#if ((Z_MIN_PIN != -1) && (Z_MAX_PIN != -1)) || ((Z_MIN_PIN == -1) && (Z_MAX_PIN == -1))
99
+#error define one of Z_MIN_PIN or Z_MAX_PIN
100
+#endif
101
+
102
+#if ((E_MIN_PIN != -1) && (E_MAX_PIN != -1)) || ((E_MIN_PIN == -1) && (E_MAX_PIN == -1))
103
+#error define one of E_MIN_PIN or E_MAX_PIN
104
+#endif
105
+
106
+#if (X_MIN_PIN == -1)
107
+#define X_HOMING_DIR 1.0
108
+#define X_ENDSTOP_PIN X_MAX_PIN
109
+#else
110
+#define X_HOMING_DIR -1.0
111
+#define X_ENDSTOP_PIN X_MIN_PIN
112
+#endif
113
+
114
+#if (Y_MIN_PIN == -1)
115
+#define Y_HOMING_DIR 1.0
116
+#define Y_ENDSTOP_PIN Y_MAX_PIN
117
+#else
118
+#define Y_HOMING_DIR -1.0
119
+#define Y_ENDSTOP_PIN Y_MIN_PIN
120
+#endif
121
+
122
+#if (Z_MIN_PIN == -1)
123
+#define Z_HOMING_DIR 1.0
124
+#define Z_ENDSTOP_PIN Z_MAX_PIN
125
+#else
126
+#define Z_HOMING_DIR -1.0
127
+#define Z_ENDSTOP_PIN Z_MIN_PIN
128
+#endif
129
+
130
+#if (E_MIN_PIN == -1)
131
+#define E_HOMING_DIR 1.0
132
+#define E_ENDSTOP_PIN E_MAX_PIN
133
+#else
134
+#define E_HOMING_DIR -1.0
135
+#define E_ENDSTOP_PIN E_MIN_PIN
136
+#endif

+ 29
- 0
include/data.h View File

@@ -0,0 +1,29 @@
1
+#ifndef _DATA_H_
2
+#define _DATA_H_
3
+
4
+#define DATA_SCHEMA_VERSION 0
5
+
6
+struct data_config_options {
7
+    float speed_x, speed_y, speed_z, speed_e;
8
+    float accel_x, accel_y, accel_z, accel_e;
9
+};
10
+
11
+struct data_config_preset {
12
+    uint8_t rows, cols;
13
+    float distance_x, distance_y;
14
+    float offset_x, offset_y;
15
+    float top_z, bottom_z;
16
+    float extrusion;
17
+};
18
+
19
+void data_init(void);
20
+void data_eeprom_write(void);
21
+
22
+struct data_config_options *data_options(void);
23
+
24
+unsigned int data_preset_count(void);
25
+struct data_config_preset *data_preset(unsigned int i);
26
+void data_preset_add(struct data_config_preset preset);
27
+void data_preset_remove(unsigned int i);
28
+
29
+#endif // _DATA_H_

+ 26
- 0
include/statemachine.h View File

@@ -71,4 +71,30 @@ private:
71 71
     Array<State *, 42> children;
72 72
 };
73 73
 
74
+class StateDynamicMenu : public State {
75
+public:
76
+    StateDynamicMenu(State *_parent = NULL);
77
+
78
+    typedef int(*CountFuncPtr)(void);
79
+    typedef const char *(*GetFuncPtr)(int);
80
+    typedef void(*CallFuncPtr)(int);
81
+
82
+    void dataCount(CountFuncPtr count);
83
+    void dataGet(GetFuncPtr get);
84
+    void dataCall(CallFuncPtr call);
85
+
86
+    virtual void enterState(void);
87
+    virtual void inState(StateMachineInput smi);
88
+
89
+private:
90
+    void display(void);
91
+
92
+    CountFuncPtr countFunc;
93
+    GetFuncPtr getFunc;
94
+    CallFuncPtr callFunc;
95
+
96
+    int count;
97
+    Array<const char *, 42> contents;
98
+};
99
+
74 100
 #endif // _STATE_MACHINE_H_

+ 164
- 0
src/data.cpp View File

@@ -0,0 +1,164 @@
1
+#include <Arduino.h>
2
+#include <EEPROM.h>
3
+
4
+#include "config.h"
5
+#include "config_pins.h"
6
+#include "data.h"
7
+
8
+#define EEPROM_SIZE 4096
9
+
10
+struct data_config {
11
+    uint8_t data_schema_version;
12
+    uint8_t preset_count;
13
+    uint32_t checksum;
14
+    struct data_config_options options;
15
+    struct data_config_preset *presets;
16
+};
17
+
18
+static struct data_config d;
19
+
20
+static unsigned int max_presets(void) {
21
+    unsigned int s = EEPROM_SIZE - sizeof(struct data_config) + sizeof(struct data_config_preset *);
22
+    return s / sizeof(struct data_config_preset);
23
+}
24
+
25
+static uint32_t data_checksum(struct data_config *data) {
26
+    uint32_t c = 0;
27
+
28
+    uint8_t *t = (uint8_t *)data;
29
+    for (unsigned int i = 0; i < sizeof(struct data_config); i++) {
30
+        c ^= t[i];
31
+    }
32
+
33
+    for (unsigned int i = 0; i < data->preset_count; i++) {
34
+        t = (uint8_t *)(&data->presets[i]);
35
+        for (unsigned int j = 0; j < sizeof(struct data_config_preset); j++) {
36
+            c ^= t[j];
37
+        }
38
+    }
39
+
40
+    return c;
41
+}
42
+
43
+static bool data_eeprom_read(void) {
44
+    struct data_config config;
45
+    uint8_t *data = (uint8_t *)&config;
46
+
47
+    // read meta-data and settings
48
+    unsigned int s = sizeof(struct data_config);
49
+    for (unsigned int i = 0; i < s; i++) {
50
+        data[i] = EEPROM.read(i);
51
+    }
52
+
53
+    if (config.preset_count > 0) {
54
+        config.presets = (struct data_config_preset *)malloc(config.preset_count * sizeof(struct data_config_preset));
55
+        if (config.presets == NULL) {
56
+            Serial.print(F("Alloc "));
57
+            return false;
58
+        }
59
+
60
+        if (config.preset_count > max_presets()) {
61
+            Serial.print(F("Preset "));
62
+            return false;
63
+        }
64
+
65
+        // read presets
66
+        for (unsigned int i = 0; i < config.preset_count; i++) {
67
+            data = (uint8_t *)(&config.presets[i]);
68
+            for (unsigned int j = 0; j < sizeof(struct data_config_preset); j++) {
69
+                data[j] = EEPROM.read(s + j);
70
+                s += sizeof(struct data_config_preset);
71
+            }
72
+        }
73
+    } else {
74
+        config.presets = NULL;
75
+    }
76
+
77
+    // verify checksum
78
+    uint32_t checksum = data_checksum(&config);
79
+    if (config.checksum == checksum) {
80
+        // verify version
81
+        if (config.data_schema_version == DATA_SCHEMA_VERSION) {
82
+            if (d.presets != NULL) {
83
+                free(d.presets);
84
+            }
85
+            d = config;
86
+
87
+            return true;
88
+        } else {
89
+            Serial.print(F("Version "));
90
+            return false;
91
+        }
92
+    } else {
93
+        Serial.print(F("Checksum "));
94
+        return false;
95
+    }
96
+}
97
+
98
+void data_eeprom_write(void) {
99
+    d.checksum = data_checksum(&d);
100
+
101
+    // write meta-data and settings
102
+    uint8_t *data = (uint8_t *)&d;
103
+    unsigned int s = sizeof(struct data_config);
104
+    for (unsigned int i = 0; i < s; i++) {
105
+        EEPROM.update(i, data[i]);
106
+    }
107
+
108
+    // write presets
109
+    for (unsigned int i = 0; i < d.preset_count; i++) {
110
+        data = (uint8_t *)(&d.presets[i]);
111
+        for (unsigned int j = 0; j < sizeof(struct data_config_preset); j++) {
112
+            EEPROM.update(s + j, data[j]);
113
+            s += sizeof(struct data_config_preset);
114
+        }
115
+    }
116
+}
117
+
118
+void data_init(void) {
119
+    d.data_schema_version = DATA_SCHEMA_VERSION;
120
+    d.preset_count = 0;
121
+    d.checksum = 0;
122
+
123
+    d.options.speed_x = XY_MAX_SPEED;
124
+    d.options.speed_y = XY_MAX_SPEED;
125
+    d.options.speed_z = Z_MAX_SPEED;
126
+    d.options.speed_e = E_MAX_SPEED;
127
+
128
+    d.options.accel_x = XY_MAX_ACCEL;
129
+    d.options.accel_y = XY_MAX_ACCEL;
130
+    d.options.accel_z = Z_MAX_ACCEL;
131
+    d.options.accel_e = E_MAX_ACCEL;
132
+
133
+    d.presets = NULL;
134
+
135
+    Serial.print(F("EEPROM read... "));
136
+    if (!data_eeprom_read()) {
137
+        Serial.println(F("Error"));
138
+    } else {
139
+        Serial.println(F("Ok"));
140
+    }
141
+}
142
+
143
+struct data_config_options *data_options(void) {
144
+    return &d.options;
145
+}
146
+
147
+unsigned int data_preset_count(void) {
148
+    return d.preset_count;
149
+}
150
+
151
+struct data_config_preset *data_preset(unsigned int i) {
152
+    if (i < d.preset_count) {
153
+        return &d.presets[i];
154
+    }
155
+    return NULL;
156
+}
157
+
158
+void data_preset_add(struct data_config_preset preset) {
159
+
160
+}
161
+
162
+void data_preset_remove(unsigned int i) {
163
+
164
+}

+ 4
- 0
src/main.cpp View File

@@ -3,6 +3,7 @@
3 3
 #include "config.h"
4 4
 #include "config_pins.h"
5 5
 #include "common.h"
6
+#include "data.h"
6 7
 #include "encoder.h"
7 8
 #include "lcd.h"
8 9
 #include "steppers.h"
@@ -20,6 +21,9 @@ void setup() {
20 21
     Serial.print(F("Version: "));
21 22
     Serial.println(FIRMWARE_VERSION);
22 23
 
24
+    Serial.println(F("Init data"));
25
+    data_init();
26
+
23 27
     Serial.println(F("Init encoder"));
24 28
     encoder_init();
25 29
 

+ 35
- 0
src/statemachine.cpp View File

@@ -78,3 +78,38 @@ void StateMenu::enterState(void) {
78 78
 void StateMenu::inState(struct StateMachineInput smi) {
79 79
 
80 80
 }
81
+
82
+// --------------------------------------
83
+
84
+StateDynamicMenu::StateDynamicMenu(State *_parent = NULL) : State(_parent) { }
85
+
86
+void StateDynamicMenu::dataCount(CountFuncPtr count) {
87
+    countFunc = count;
88
+}
89
+
90
+void StateDynamicMenu::dataGet(GetFuncPtr get) {
91
+    getFunc = get;
92
+}
93
+
94
+void StateDynamicMenu::dataCall(CallFuncPtr call) {
95
+    callFunc = call;
96
+}
97
+
98
+void StateDynamicMenu::display(void) {
99
+
100
+}
101
+
102
+void StateDynamicMenu::enterState(void) {
103
+    // cache all entries on entering state
104
+    count = countFunc();
105
+    contents.clear();
106
+    for (int i = 0; i < count; i++) {
107
+        contents.push_back(getFunc(i));
108
+    }
109
+
110
+    display();
111
+}
112
+
113
+void StateDynamicMenu::inState(StateMachineInput smi) {
114
+
115
+}

+ 21
- 0
src/states.cpp View File

@@ -2,6 +2,7 @@
2 2
 
3 3
 #include "config.h"
4 4
 #include "config_pins.h"
5
+#include "data.h"
5 6
 #include "common.h"
6 7
 #include "lcd.h"
7 8
 #include "steppers.h"
@@ -15,9 +16,14 @@ StateText sm_do_homing = StateText(&sm_ask_homing);
15 16
 StateMenu sm_menu = StateMenu(&sm_do_homing);
16 17
 
17 18
 StateMenu sm_auto = StateMenu(&sm_menu);
19
+StateDynamicMenu sm_presets = StateDynamicMenu(&sm_auto);
20
+StateDynamicMenu sm_new_preset = StateDynamicMenu(&sm_auto);
21
+StateDynamicMenu sm_mod_preset = StateDynamicMenu(&sm_auto);
22
+StateDynamicMenu sm_del_preset = StateDynamicMenu(&sm_auto);
18 23
 
19 24
 StateMenu sm_config = StateMenu(&sm_menu);
20 25
 
26
+
21 27
 // --------------------------------------
22 28
 
23 29
 State *current_state = NULL;
@@ -58,6 +64,21 @@ void states_init(void) {
58 64
     sm_auto.setTitle("Filling Menu");
59 65
     sm_auto.setChild(&sm_menu);
60 66
 
67
+    sm_presets.setTitle("Presets");
68
+    sm_presets.dataCount([]() {
69
+        return (int)data_preset_count();
70
+    });
71
+    sm_presets.dataGet([](int i) {
72
+        // TODO can not build a name string here
73
+        // dynamically. need to have a name stored
74
+        // somewhere, in data/eeprom, for each preset
75
+        // that we can pass here
76
+    });
77
+
78
+    sm_new_preset.setTitle("New Preset");
79
+    sm_mod_preset.setTitle("Modify Preset");
80
+    sm_del_preset.setTitle("Delete Preset");
81
+
61 82
     // ----------------------------------
62 83
 
63 84
     sm_config.setTitle("Configuration");

+ 230
- 16
src/steppers.cpp View File

@@ -3,6 +3,7 @@
3 3
 
4 4
 #include "config.h"
5 5
 #include "config_pins.h"
6
+#include "lcd.h"
6 7
 #include "steppers.h"
7 8
 
8 9
 static AccelStepper stepper_x(AccelStepper::DRIVER, X_STEP_PIN, X_DIR_PIN, 0, 0, false);
@@ -29,8 +30,27 @@ enum stepper_states {
29 30
 };
30 31
 
31 32
 static stepper_states state = step_disabled;
33
+static unsigned long steppers_home_move_start_time = 0;
32 34
 
33 35
 void steppers_init(void) {
36
+    pinMode(X_ENDSTOP_PIN, INPUT);
37
+    pinMode(Y_ENDSTOP_PIN, INPUT);
38
+    pinMode(Z_ENDSTOP_PIN, INPUT);
39
+    pinMode(E_ENDSTOP_PIN, INPUT);
40
+
41
+    pinMode(X_ENABLE_PIN, OUTPUT);
42
+    pinMode(X_STEP_PIN, OUTPUT);
43
+    pinMode(X_DIR_PIN, OUTPUT);
44
+    pinMode(Y_ENABLE_PIN, OUTPUT);
45
+    pinMode(Y_STEP_PIN, OUTPUT);
46
+    pinMode(Y_DIR_PIN, OUTPUT);
47
+    pinMode(Z_ENABLE_PIN, OUTPUT);
48
+    pinMode(Z_STEP_PIN, OUTPUT);
49
+    pinMode(Z_DIR_PIN, OUTPUT);
50
+    pinMode(E0_ENABLE_PIN, OUTPUT);
51
+    pinMode(E0_STEP_PIN, OUTPUT);
52
+    pinMode(E0_DIR_PIN, OUTPUT);
53
+
34 54
     stepper_x.setEnablePin(X_ENABLE_PIN);
35 55
     stepper_x.setMaxSpeed(XY_MAX_SPEED * XY_STEPS_PER_MM);
36 56
     stepper_x.setAcceleration(XY_MAX_ACCEL * XY_STEPS_PER_MM);
@@ -48,27 +68,177 @@ void steppers_init(void) {
48 68
     stepper_e.setAcceleration(E_MAX_ACCEL * E_STEPS_PER_MM);
49 69
 }
50 70
 
71
+static void steppers_initiate_home(int axis, int phase) {
72
+    steppers_home_move_start_time = millis();
73
+
74
+    if (axis == 0) {
75
+        // x
76
+        if (phase == 0) {
77
+            state = step_homing_x_fast;
78
+            stepper_x.setSpeed(X_HOMING_DIR * X_AXIS_MOVEMENT_DIR * XY_FAST_HOME_SPEED * XY_STEPS_PER_MM);
79
+        } else if (phase == 1) {
80
+            state = step_homing_x_back;
81
+            stepper_x.setSpeed(-1.0 * X_HOMING_DIR * X_AXIS_MOVEMENT_DIR * XY_FAST_HOME_SPEED * XY_STEPS_PER_MM);
82
+        } else if (phase == 2) {
83
+            state = step_homing_x_slow;
84
+            stepper_x.setSpeed(X_HOMING_DIR * X_AXIS_MOVEMENT_DIR * XY_SLOW_HOME_SPEED * XY_STEPS_PER_MM);
85
+        }
86
+    } else if (axis == 1) {
87
+        // y
88
+        if (phase == 0) {
89
+            state = step_homing_y_fast;
90
+            stepper_y.setSpeed(Y_HOMING_DIR * Y_AXIS_MOVEMENT_DIR * XY_FAST_HOME_SPEED * XY_STEPS_PER_MM);
91
+        } else if (phase == 1) {
92
+            state = step_homing_y_back;
93
+            stepper_y.setSpeed(-1.0 * Y_HOMING_DIR * Y_AXIS_MOVEMENT_DIR * XY_FAST_HOME_SPEED * XY_STEPS_PER_MM);
94
+        } else if (phase == 2) {
95
+            state = step_homing_y_slow;
96
+            stepper_y.setSpeed(Y_HOMING_DIR * Y_AXIS_MOVEMENT_DIR * XY_SLOW_HOME_SPEED * XY_STEPS_PER_MM);
97
+        }
98
+    } else if (axis == 2) {
99
+        // z
100
+        if (phase == 0) {
101
+            state = step_homing_z_fast;
102
+            stepper_z.setSpeed(Z_HOMING_DIR * Z_AXIS_MOVEMENT_DIR * Z_FAST_HOME_SPEED * Z_STEPS_PER_MM);
103
+        } else if (phase == 1) {
104
+            state = step_homing_z_back;
105
+            stepper_z.setSpeed(-1.0 * Z_HOMING_DIR * Z_AXIS_MOVEMENT_DIR * Z_FAST_HOME_SPEED * Z_STEPS_PER_MM);
106
+        } else if (phase == 2) {
107
+            state = step_homing_z_slow;
108
+            stepper_z.setSpeed(Z_HOMING_DIR * Z_AXIS_MOVEMENT_DIR * Z_SLOW_HOME_SPEED * Z_STEPS_PER_MM);
109
+        }
110
+    } else if (axis == 3) {
111
+        // e
112
+        if (phase == 0) {
113
+            state = step_homing_e_fast;
114
+            stepper_e.setSpeed(E_HOMING_DIR * E_AXIS_MOVEMENT_DIR * E_FAST_HOME_SPEED * E_STEPS_PER_MM);
115
+        } else if (phase == 1) {
116
+            state = step_homing_e_back;
117
+            stepper_e.setSpeed(-1.0 * E_HOMING_DIR * E_AXIS_MOVEMENT_DIR * E_FAST_HOME_SPEED * E_STEPS_PER_MM);
118
+        } else if (phase == 2) {
119
+            state = step_homing_e_slow;
120
+            stepper_e.setSpeed(E_HOMING_DIR * E_AXIS_MOVEMENT_DIR * E_SLOW_HOME_SPEED * E_STEPS_PER_MM);
121
+        }
122
+    } else {
123
+        Serial.println(F("home_init error: invalid axis"));
124
+    }
125
+}
126
+
127
+static bool steppers_home_switch(int axis) {
128
+    if (axis == 0) {
129
+        return digitalRead(X_ENDSTOP_PIN) == LOW;
130
+    } else if (axis == 1) {
131
+        return digitalRead(Y_ENDSTOP_PIN) == LOW;
132
+    } else if (axis == 2) {
133
+        return digitalRead(Z_ENDSTOP_PIN) == LOW;
134
+    } else if (axis == 3) {
135
+        return digitalRead(E_ENDSTOP_PIN) == LOW;
136
+    } else {
137
+        Serial.println(F("home_switch error: invalid axis"));
138
+    }
139
+    return true;
140
+}
141
+
51 142
 bool steppers_run(void) {
52 143
     if (state == step_homing_x_fast) {
144
+        if (steppers_home_switch(0)) {
145
+            steppers_initiate_home(0, 1);
146
+        } else {
147
+            stepper_x.runSpeed();
148
+        }
53 149
     } else if (state == step_homing_x_back) {
150
+        unsigned long end_time = steppers_home_move_start_time + XY_HOME_BACK_OFF_TIME;
151
+        if ((!steppers_home_switch(0)) && (millis() >= end_time)) {
152
+            steppers_initiate_home(0, 2);
153
+        } else {
154
+            stepper_x.runSpeed();
155
+        }
54 156
     } else if (state == step_homing_x_slow) {
157
+        if (steppers_home_switch(0)) {
158
+            steppers_initiate_home(1, 0);
159
+        } else {
160
+            stepper_x.runSpeed();
161
+        }
55 162
     } else if (state == step_homing_y_fast) {
163
+        if (steppers_home_switch(1)) {
164
+            steppers_initiate_home(1, 1);
165
+        } else {
166
+            stepper_y.runSpeed();
167
+        }
56 168
     } else if (state == step_homing_y_back) {
169
+        unsigned long end_time = steppers_home_move_start_time + XY_HOME_BACK_OFF_TIME;
170
+        if ((!steppers_home_switch(1)) && (millis() >= end_time)) {
171
+            steppers_initiate_home(1, 2);
172
+        } else {
173
+            stepper_y.runSpeed();
174
+        }
57 175
     } else if (state == step_homing_y_slow) {
176
+        if (steppers_home_switch(1)) {
177
+            steppers_initiate_home(3, 0);
178
+        } else {
179
+            stepper_y.runSpeed();
180
+        }
58 181
     } else if (state == step_homing_z_fast) {
182
+        if (steppers_home_switch(2)) {
183
+            steppers_initiate_home(2, 1);
184
+        } else {
185
+            stepper_z.runSpeed();
186
+        }
59 187
     } else if (state == step_homing_z_back) {
188
+        unsigned long end_time = steppers_home_move_start_time + Z_HOME_BACK_OFF_TIME;
189
+        if ((!steppers_home_switch(2)) && (millis() >= end_time)) {
190
+            steppers_initiate_home(2, 2);
191
+        } else {
192
+            stepper_z.runSpeed();
193
+        }
60 194
     } else if (state == step_homing_z_slow) {
195
+        if (steppers_home_switch(2)) {
196
+            steppers_initiate_home(0, 0);
197
+        } else {
198
+            stepper_z.runSpeed();
199
+        }
61 200
     } else if (state == step_homing_e_fast) {
201
+        if (steppers_home_switch(3)) {
202
+            steppers_initiate_home(3, 1);
203
+        } else {
204
+            stepper_e.runSpeed();
205
+        }
62 206
     } else if (state == step_homing_e_back) {
207
+        unsigned long end_time = steppers_home_move_start_time + E_HOME_BACK_OFF_TIME;
208
+        if ((!steppers_home_switch(3)) && (millis() >= end_time)) {
209
+            steppers_initiate_home(3, 2);
210
+        } else {
211
+            stepper_e.runSpeed();
212
+        }
63 213
     } else if (state == step_homing_e_slow) {
64
-    }
214
+        if (steppers_home_switch(3)) {
215
+            state = step_homed;
216
+            return false;
217
+        } else {
218
+            stepper_z.runSpeed();
219
+        }
220
+    } else if (state != step_disabled) {
221
+        for (int i = 0; i < 4; i++) {
222
+            if (steppers_home_switch(i)) {
223
+                Serial.print(F("ERROR: endstop hit on "));
224
+                Serial.println(i);
65 225
 
66
-    boolean x = stepper_x.run();
67
-    boolean y = stepper_y.run();
68
-    boolean z = stepper_z.run();
69
-    boolean e = stepper_e.run();
226
+                // TODO proper error handling?
227
+                lcd_clear();
228
+                lcd_set_heading("ERROR");
229
+                lcd_set_text("Endstop hit. Aborting!");
230
+                while (1) { }
231
+            }
232
+        }
233
+        boolean x = stepper_x.run();
234
+        boolean y = stepper_y.run();
235
+        boolean z = stepper_z.run();
236
+        boolean e = stepper_e.run();
237
+
238
+        return x || y || z || e;
239
+    }
70 240
 
71
-    return x || y || z || e;
241
+    return true;
72 242
 }
73 243
 
74 244
 bool steppers_homed(void) {
@@ -76,8 +246,7 @@ bool steppers_homed(void) {
76 246
 }
77 247
 
78 248
 void steppers_start_homing(void) {
79
-    state = step_homing_x_fast;
80
-
249
+    steppers_initiate_home(2, 0);
81 250
 }
82 251
 
83 252
 static int steppers_move_axis(AccelStepper &axis, long pos) {
@@ -91,45 +260,90 @@ static int steppers_move_axis(AccelStepper &axis, long pos) {
91 260
         state = step_not_homed;
92 261
     }
93 262
 
263
+    if (!steppers_homed()) {
264
+        Serial.println(F("WARNING: un-homed move!"));
265
+    }
266
+
94 267
     axis.moveTo(pos);
268
+    return 0;
95 269
 }
96 270
 
97 271
 int steppers_move_x(long pos) {
98 272
     Serial.print(F("Moving X to "));
99 273
     Serial.print(pos);
100 274
     Serial.print(F(" mm ("));
101
-    Serial.print(pos * XY_STEPS_PER_MM);
275
+    Serial.print(pos * XY_STEPS_PER_MM * X_AXIS_MOVEMENT_DIR);
102 276
     Serial.println(F(" steps)"));
103 277
 
104
-    return steppers_move_axis(stepper_x, pos * XY_STEPS_PER_MM);
278
+    if (pos < X_AXIS_MIN) {
279
+        Serial.println(F("Move below X_AXIS_MIN!"));
280
+        return -1;
281
+    }
282
+
283
+    if (pos > X_AXIS_MAX) {
284
+        Serial.println(F("Move above X_AXIS_MAX!"));
285
+        return -1;
286
+    }
287
+
288
+    return steppers_move_axis(stepper_x, pos * XY_STEPS_PER_MM * X_AXIS_MOVEMENT_DIR);
105 289
 }
106 290
 
107 291
 int steppers_move_y(long pos) {
108 292
     Serial.print(F("Moving Y to "));
109 293
     Serial.print(pos);
110 294
     Serial.print(F(" mm ("));
111
-    Serial.print(pos * XY_STEPS_PER_MM);
295
+    Serial.print(pos * XY_STEPS_PER_MM * Y_AXIS_MOVEMENT_DIR);
112 296
     Serial.println(F(" steps)"));
113 297
 
114
-    return steppers_move_axis(stepper_y, pos * XY_STEPS_PER_MM);
298
+    if (pos < Y_AXIS_MIN) {
299
+        Serial.println(F("Move below Y_AXIS_MIN!"));
300
+        return -1;
301
+    }
302
+
303
+    if (pos > Y_AXIS_MAX) {
304
+        Serial.println(F("Move above Y_AXIS_MAX!"));
305
+        return -1;
306
+    }
307
+
308
+    return steppers_move_axis(stepper_y, pos * XY_STEPS_PER_MM * Y_AXIS_MOVEMENT_DIR);
115 309
 }
116 310
 
117 311
 int steppers_move_z(long pos) {
118 312
     Serial.print(F("Moving Z to "));
119 313
     Serial.print(pos);
120 314
     Serial.print(F(" mm ("));
121
-    Serial.print(pos * Z_STEPS_PER_MM);
315
+    Serial.print(pos * Z_STEPS_PER_MM * Z_AXIS_MOVEMENT_DIR);
122 316
     Serial.println(F(" steps)"));
123 317
 
124
-    return steppers_move_axis(stepper_z, pos * Z_STEPS_PER_MM);
318
+    if (pos < Z_AXIS_MIN) {
319
+        Serial.println(F("Move below Z_AXIS_MIN!"));
320
+        return -1;
321
+    }
322
+
323
+    if (pos > Z_AXIS_MAX) {
324
+        Serial.println(F("Move above Z_AXIS_MAX!"));
325
+        return -1;
326
+    }
327
+
328
+    return steppers_move_axis(stepper_z, pos * Z_STEPS_PER_MM * Z_AXIS_MOVEMENT_DIR);
125 329
 }
126 330
 
127 331
 int steppers_move_e(long pos) {
128 332
     Serial.print(F("Moving E to "));
129 333
     Serial.print(pos);
130 334
     Serial.print(F(" mm ("));
131
-    Serial.print(pos * E_STEPS_PER_MM);
335
+    Serial.print(pos * E_STEPS_PER_MM * E_AXIS_MOVEMENT_DIR);
132 336
     Serial.println(F(" steps)"));
133 337
 
134
-    return steppers_move_axis(stepper_e, pos * E_STEPS_PER_MM);
338
+    if (pos < E_AXIS_MIN) {
339
+        Serial.println(F("Move below E_AXIS_MIN!"));
340
+        return -1;
341
+    }
342
+
343
+    if (pos > E_AXIS_MAX) {
344
+        Serial.println(F("Move above E_AXIS_MAX!"));
345
+        return -1;
346
+    }
347
+
348
+    return steppers_move_axis(stepper_e, pos * E_STEPS_PER_MM * E_AXIS_MOVEMENT_DIR);
135 349
 }

Loading…
Cancel
Save