-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathmain.ino
297 lines (244 loc) · 8.37 KB
/
main.ino
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
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
#define motor0_A_PIN 29
#define motor0_B_PIN 30
#define motor0_PWM_PIN 4
#define motor1_A_PIN 31
#define motor1_B_PIN 32
#define motor1_PWM_PIN 5
#define motor2_A_PIN 33
#define motor2_B_PIN 34
#define motor2_PWM_PIN 6
#define motor3_A_PIN 35
#define motor3_B_PIN 36
#define motor3_PWM_PIN 7
#define motor4_A_PIN 37
#define motor4_B_PIN 38
#define motor4_PWM_PIN 8
#define motor5_A_PIN 39
#define motor5_B_PIN 40
#define motor5_PWM_PIN 9
#define motor0_INT_PIN 19
#define motor0_SIG_PIN 25
#define motor4_INT_PIN 2
#define motor4_SIG_PIN 26
#define motor5_INT_PIN 3
#define motor5_SIG_PIN 27
#include "SparkFunLSM6DS3.h"
#include "pins_arduino.h"
#include "SPI.h"
#include "nc2_toolkit.h"
#include "interpolation.h"
#include "buttonUpd.h"
#include "motor_control.h"
#include <Wire.h>
using namespace nc;
timer_ms global_time(0);
timer_ms my_time(0);
/*gyro handling*/
LSM6DS3 raw_gyro(I2C_MODE, 0x6A);
crude_integrator<micros> gyro_integrator(
0.000001 * D2R,
0.8856
);
/*motor_suite motors{{.value={
{26, 28, 9},
{30, 32, 8},
{42, 43, 7},
{47, 48, 6}
}}};*/
template<typename T>
struct ni_point {
T payload;
long timestamp;
};
template<typename T>
class ni_sequence {
public:
ni_sequence(ni_point<T>* sequence_ptr, size_t size);
T get(long timestamp);
private:
unsigned find_left_point_index(long timestamp);
ni_point<T>* sequence_ptr;
size_t size;
};
template<typename T>
ni_sequence<T>::ni_sequence(ni_point<T>* sequence_ptr, size_t size) :
sequence_ptr(sequence_ptr), size(size)
{}
template<typename T>
unsigned ni_sequence<T>::find_left_point_index(long timestamp) {
unsigned current_index = size - 1;
while (sequence_ptr[current_index].timestamp > timestamp) {
current_index--;
}
return current_index;
}
template<typename T>
T ni_sequence<T>::get(long timestamp) {
unsigned left_point_index = find_left_point_index(timestamp);
return sequence_ptr[left_point_index].payload;
}
struct my_payload {
short v1;
short v2;
short p1;
short p2;
};
#define masive_size 18
#define delta_pos 0
#define delta_speed 0.5
#define delta_time 100
ni_point<my_payload> masive[masive_size] = { //2-rats 1-soldiers
//v1 v2 p1 p2 time
{{100 * delta_speed, 100 * delta_speed, 80 + delta_pos, 80 + delta_pos}, 0},
{{100 * delta_speed, 100 * delta_speed, 50 + delta_pos, 50 + delta_pos}, 2800 + delta_time},
{{100 * delta_speed, 100 * delta_speed, 80 + delta_pos, 80 + delta_pos}, 3700 + 2 * delta_time},
{{100 * delta_speed, 100 * delta_speed, 50 + delta_pos, 50 + delta_pos}, 4600 + 3 * delta_time},
{{100 * delta_speed, 100 * delta_speed, 80 + delta_pos, 80 + delta_pos}, 5500 + 4 * delta_time},
{{100 * delta_speed, 100 * delta_speed, 110 + delta_pos, 110 + delta_pos}, 6600 + 5 * delta_time},
{{100 * delta_speed, 100 * delta_speed, 80 + delta_pos, 80 + delta_pos}, 7700 + 6 * delta_time},
{{100 * delta_speed, 100 * delta_speed, 110 + delta_pos, 110 + delta_pos}, 8800 + 7 * delta_time},
{{100 * delta_speed, 100 * delta_speed, 80 + delta_pos, 80 + delta_pos}, 9900 + 8 * delta_time},
{{120 * delta_speed, 60 * delta_speed, 120 + delta_pos, 80 + delta_pos}, 11000 + 9 * delta_time},
{{120 * delta_speed, 60 * delta_speed, 120 + delta_pos, 65 + delta_pos}, 11250 + 10 * delta_time},
{{100 * delta_speed, 60 * delta_speed, 80 + delta_pos, 65 + delta_pos}, 12300 + 11 * delta_time},
{{120 * delta_speed, 60 * delta_speed, 120 + delta_pos, 65 + delta_pos}, 13200 + 12 * delta_time},
{{120 * delta_speed, 60 * delta_speed, 120 + delta_pos, 55 + delta_pos}, 14050 + 13 * delta_time},
{{100 * delta_speed, 60 * delta_speed, 80 + delta_pos, 55 + delta_pos}, 14700 + 14 * delta_time},
{{120 * delta_speed, 60 * delta_speed, 120 + delta_pos, 55 + delta_pos}, 15800 + 15 * delta_time},
{{120 * delta_speed, 60 * delta_speed, 120 + delta_pos, 25 + delta_pos}, 16450 + 16 * delta_time},
{{100 * delta_speed, 60 * delta_speed, 90 + delta_pos, 25 + delta_pos}, 17150 + 17 * delta_time},
};
ni_sequence<my_payload> sequence(masive, masive_size);
//sequence.get(global_time).v1
void setup() {
pinMode(motor0_A_PIN, OUTPUT);
pinMode(motor0_B_PIN, OUTPUT);
pinMode(motor0_PWM_PIN, OUTPUT);
pinMode(motor1_A_PIN, OUTPUT);
pinMode(motor1_B_PIN, OUTPUT);
pinMode(motor1_PWM_PIN, OUTPUT);
pinMode(motor2_A_PIN, OUTPUT);
pinMode(motor2_B_PIN, OUTPUT);
pinMode(motor2_PWM_PIN, OUTPUT);
pinMode(motor3_A_PIN, OUTPUT);
pinMode(motor3_B_PIN, OUTPUT);
pinMode(motor3_PWM_PIN, OUTPUT);
pinMode(motor4_A_PIN, OUTPUT);
pinMode(motor4_B_PIN, OUTPUT);
pinMode(motor4_PWM_PIN, OUTPUT);
pinMode(motor5_A_PIN, OUTPUT);
pinMode(motor5_B_PIN, OUTPUT);
pinMode(motor5_PWM_PIN, OUTPUT);
pinMode(motor0_INT_PIN, INPUT);
pinMode(motor0_SIG_PIN, INPUT);
attachInterrupt(digitalPinToInterrupt(motor0_INT_PIN), Enc0, RISING);
pinMode(motor4_INT_PIN, INPUT);
pinMode(motor4_SIG_PIN, INPUT);
attachInterrupt(digitalPinToInterrupt(motor4_INT_PIN), Enc4, RISING);
pinMode(motor5_INT_PIN, INPUT);
pinMode(motor5_SIG_PIN, INPUT);
attachInterrupt(digitalPinToInterrupt(motor5_INT_PIN), Enc5, RISING);
Serial.begin(9600);
raw_gyro.begin();
gyro_integrator.reset();
global_time = timer_ms(0);
my_time = timer_ms(0);
Wire.begin();
Wire.beginTransmission(8);
Wire.write(1);
Wire.endTransmission();
}
constexpr long iteration_duration{15};
long iterations_passed{0};
void end_iteration() {
while (global_time < iteration_duration * (iterations_passed + 1)) {};
iterations_passed++;
}
#include "zbee-handling.h"
double gyro_zero = 0;
int scene = 2; // !!! don't change if you work with customs libraries for decoration (without waiting button)
void loop() {
gyro_integrator.update(raw_gyro.readFloatGyroZ());
buttonUpd();
Serial.println(motor0_enc);
//set_motor_speeds(0, 0, 25);
switch (scene) {
case (1):
if (button3) { //wait start
scene = 2;
gyro_zero = gyro_integrator;
my_time = timer_ms(0);
set_motor_encoder_zero(); //for activate by start_button
/*Wire.beginTransmission(8);
Wire.write(2);
Wire.endTransmission();
delay(200);*/
}
break;
case (2):
set_motor_speeds(55, 0, 0); //drive
if (abs(motor0_enc) > 500) {
scene = 3;
my_time = timer_ms(0);
set_motor_encoder_zero();
Wire.beginTransmission(8);
Wire.write(3);
Wire.endTransmission();
}
break;
case (3):
set_motor_speeds(0, 0, 33); //180 turn
if (gyro_integrator > PI / 32 * 30 + gyro_zero) {
scene = 4;
my_time = timer_ms(0);
set_motor_encoder_zero();
set_motor_speeds(0, 0, 0);
/*Wire.beginTransmission(8);
Wire.write(4);
Wire.endTransmission();*/
}
break;
case (4):
set_motor_target(sequence.get(my_time).v1, sequence.get(my_time).p1, sequence.get(my_time).v2, sequence.get(my_time).p2);
if (my_time > 18300 + 18 * delta_time) {
scene = 5;
gyro_zero = gyro_integrator;
my_time = timer_ms(0);
set_motor_encoder_zero();
Wire.beginTransmission(8);
Wire.write(5);
Wire.endTransmission();
}
break;
case (5):
set_motor_speeds(0, 0, -33); //180 turn
if (gyro_integrator < -PI / 32 * 31 + gyro_zero) {
scene = 6;
my_time = timer_ms(0);
set_motor_encoder_zero();
/*Wire.beginTransmission(8);
Wire.write(6);
Wire.endTransmission();*/
}
break;
case (6):
set_motor_speeds(-55, 0, 0); //drive
if (get_motor_encoder() < -800) {
scene = 7;
my_time = timer_ms(0);
Serial.println("end");
set_motor_encoder_zero();
Wire.beginTransmission(8);
Wire.write(7);
Wire.endTransmission();
}
break;
case (7):
set_motor_target(100 * delta_speed, 0, 100 * delta_speed, 0);
if (motor4_enc < 5 and motor5_enc > -5)
stop_up_motors();
set_motor_speeds(0, 0, 0);
break;
}
end_iteration();
}