forked from danithebest91/ServoStrap
-
Notifications
You must be signed in to change notification settings - Fork 0
/
STM32_olimexino_stepper_motor_emulator
175 lines (134 loc) · 4.91 KB
/
STM32_olimexino_stepper_motor_emulator
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
/* i have made this code for the LMD18245 motor controller,
i have merged the pid code of Josh Kopel
whith the code of makerbot servo-controller board,
you can use this code on the some board changing some values.
Daniele Poddighe
external ardware require a quadrature encoder, timing slit strip and a dc motor,
all you can find inside an old printer, i have took it from canon and hp printers(psc1510)
for motor controll you can choose different type of H-bridge, i have used LMD18245,
you can order 3 of it on ti.com sample request, the hardware needed is explained on the datasheet but i'm drowing
the schematic and PCB layout on eagle.
read a rotary encoder with interrupts
Encoder hooked up with common to GROUND,
encoder0PinA to pin 2, encoder0PinB to pin 4 (or pin 3 see below)
it doesn't matter which encoder pin you use for A or B
is possible to change PID costants by sending on SerialUSB interfaces the values separated by ',' in this order: KP,KD,KI
example: 5.2,3.1,0 so we have KP=5.2 KD=3.1 KI=0 is only for testing purposes, but i will leave this function with eeprom storage
*/
#define encoder0PinA 2
#define encoder0PinB 4
#define SpeedPin 9
#define DirectionPin 8
//from ramps 1.4 stepper driver
#define STEP_PIN 3
#define DIR_PIN 12
#define ENABLE_PIN 13
volatile long encoder0Pos = 0;
long target = 0;
long target1 = 0;
int amp=212;
//correction = Kp * error + Kd * (error - prevError) + kI * (sum of errors)
//PID controller constants
float KP = 6.0 ; //position multiplier (gain) 2.25
float KI = 0.1; // Intergral multiplier (gain) .25
float KD = 1.3; // derivative multiplier (gain) 1.0
int lastError = 0;
int sumError = 0;
//Integral term min/max (random value and not yet tested/verified)
int iMax = 100;
int iMin = 0;
long previousTarget = 0;
long previousMillis = 0; // will store last time LED was updated
long interval = 5; // interval at which to blink (milliseconds)
//for motor control ramps 1.4
bool newStep = false;
bool oldStep = false;
bool dir = false;
void setup() {
pinMode(encoder0PinA, INPUT);
pinMode(encoder0PinB, INPUT);
pinMode(DirectionPin, OUTPUT);
pinMode(SpeedPin, OUTPUT);
//ramps 1.4 motor control
pinMode(STEP_PIN, INPUT);
pinMode(DIR_PIN, INPUT);
attachInterrupt(2, doEncoderMotor0, CHANGE); // encoder pin on interrupt 0 - pin 2
attachInterrupt(3, countStep, RISING); //on pin 3
SerialUSB.println("start"); // a personal quirk
}
void loop(){
while (SerialUSB.available() > 0) {
KP = SerialUSB.read();
KD = SerialUSB.read();
KI = SerialUSB.read();
SerialUSB.println(KP);
SerialUSB.println(KD);
SerialUSB.println(KI);
}
if(millis() - previousTarget > 500){ //enable this code only for test purposes
SerialUSB.print(encoder0Pos);
SerialUSB.print(',');
SerialUSB.println(target1);
previousTarget=millis();
}
target = target1;
docalc();
}
void docalc() {
if (millis() - previousMillis > interval)
{
previousMillis = millis(); // remember the last time we blinked the LED
long error = encoder0Pos - target ; // find the error term of current position - target
//generalized PID formula
//correction = Kp * error + Kd * (error - prevError) + kI * (sum of errors)
long ms = KP * error + KD * (error - lastError) +KI * (sumError);
lastError = error;
sumError += error;
//scale the sum for the integral term
if(sumError > iMax) {
sumError = iMax;
} else if(sumError < iMin){
sumError = iMin;
}
if(ms > 0){
digitalWrite ( DirectionPin ,HIGH );
}
if(ms < 0){
digitalWrite ( DirectionPin , LOW );
ms = -1 * ms;
}
int motorspeed = map(ms,0,amp,0,255);
if( motorspeed >= 255) motorspeed=255;
//analogWrite ( SpeedPin, (255 - motorSpeed) );
analogWrite ( SpeedPin, motorspeed );
//SerialUSB.print ( ms );
//SerialUSB.print ( ',' );
//SerialUSB.println ( motorspeed );
}
}
void doEncoderMotor0(){
if (digitalRead(encoder0PinA) == HIGH) { // found a low-to-high on channel A
if (digitalRead(encoder0PinB) == LOW) { // check channel B to see which way
// encoder is turning
encoder0Pos = encoder0Pos - 1; // CCW
}
else {
encoder0Pos = encoder0Pos + 1; // CW
}
}
else // found a high-to-low on channel A
{
if (digitalRead(encoder0PinB) == LOW) { // check channel B to see which way
// encoder is turning
encoder0Pos = encoder0Pos + 1; // CW
}
else {
encoder0Pos = encoder0Pos - 1; // CCW
}
}
}
void countStep(){
dir = digitalRead(DIR_PIN);
if (dir) target1++;
else target1--;
}