-
Notifications
You must be signed in to change notification settings - Fork 0
/
carrito.ino
411 lines (333 loc) · 10.5 KB
/
carrito.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
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
/*
* Pin mapping
*
* *** NRF24L01 Radio ***
* Radio Arduino
* CE -> 9
* CSN -> 10 (Hardware SPI SS)
* MOSI -> 11 (Hardware SPI MOSI)
* MISO -> 12 (Hardware SPI MISO)
* SCK -> 13 (Hardware SPI SCK)
* IRQ -> No connection
* VCC -> No more than 3.6 volts
* GND -> GND
*
* *** DIRECTION MOTOR ***
* pushed via SPI to the 74HC595 on the upper nibble but is uses ...
* 8 - as SPI CS for the shift register
*
* *** POWER MOTOR ***
* 6 - PWM motor speed
* 5 - motor direction (low forward, high reverse)
*
* *** DIRECTION LIMIT SWITCHES ***
* A0 - will float in 1/2 V
* and will fire 0 or 1023 on each switch hit
*
* ** CENTER HALL sensor***
* 2 - Will be low when direction is centered
*
* *** ULTRASONIC RADAR ***
* 5 - trigger
* 6 - Echo
*
*/
//~ /***** SONAR *****/
//~ #include <HCSR04.h>
//~ UltraSonicDistanceSensor distanceSensor(5, 6);
/***** NRF24L01 *****/
#include <SPI.h>
#include <NRFLite.h>
// Our radio's id. The transmitter will send to this id.
const static uint8_t RADIO_ID = 18;
const static uint8_t PIN_RADIO_CE = 9;
const static uint8_t PIN_RADIO_CSN = 10;
/*************************************************************************
* Radio data structure explained:
*
* We will pass just relative values, aka, increments
*
* -> Speed: (int16)
* motor speed increments, every tap increment it in a fixed val
* the same for decrements
* -> Speed hold (bool)
* true if we are holding the actual speed, false if we must set
* the motor free (this means that we keep the FWD/REV key pressed)
* -> Turn: (int16)
* Turn direction increments, every tap increment it in a fixed val
* the same for decrements
* -> Turn hold (bool)
* True if we are holding any direction key.
* -> Options; (unsigned long)
* really 4 bytes, first one is bit mapped to options as
* lights, siren, etc... the others will be worked out
*************************************************************************/
// Any packet up to 32 bytes can be sent.
struct RadioPacket {
unsigned long serial = 0;
int speed;
bool speed_hold;
int turn;
bool turn_hold;
bool stop = 0;
bool lookAhead = 0;
unsigned long options;
};
// instantiate
NRFLite _radio;
RadioPacket _radioData;
/***** Stepper motor *****/
#include "stepperunipolar.h"
// instantiate it using
stepperunipolar dirMot(UNIPOLAR_WAVE);
/************************************************************************/
// constants
#define motorSpeedPin (6) // pin that will be controlling the
// PWM speed of the motor
#define motorDirectionPin (5) // set the direction of rotation
#define maxSpeed (255) // maximum speed
#define dirLimitPin (A3) // Analog pin for limit switches
#define dirHall (2) // pin in wich is the front hall
#define dirLatch (8) // latch or CS for the shift register
// Variables
volatile bool center = false; // changed by an interrupt, must be reset after read high
unsigned long pktSerial = 0; // serial to sign for duplicated packets
int speed = 0; // will be mapped from -255 to 0-255
int turn = 0; // this will be steps in each direction
bool direction = 0; // 0 is forward, 1 is backwards
float wallDistance = -1.0; // distance measured from the sensor
// to the wall
byte shiftOptions = 0; // shift register options, you can only set
// the lower four, the upper four are the
// direction motor control bits
// Serial DEBUG
//~ #define SDEBUG 0
/************************************************************************/
// interrupt rutine
void centerHit() {
center = true;
}
// set motion speed, just set the PWM value against the limit
void setSpeed(int val) {
// local var
byte lval = byte(abs(val));
// set global var value
byte lspeed = map(lval, 0, 255, 0, maxSpeed);
// apply
analogWrite(motorSpeedPin, lspeed);
}
// set direction of rotatio of the power motor
// 0 is forward, 1 is back
void setDirection(bool dir) {
// set global var
direction = dir;
// apply
digitalWrite(motorDirectionPin, direction);
}
// stop motion of the motor
void motionStop() {
// invert the motor direction for a brief time
// keep the speed
setDirection(!direction);
// delay proportional to the speed
delay(abs(speed));
// stop the motor, stop speed
speed = 0;
// the increment factor depends on inertia and hance on the weight
// of the car, you must tweak it to suit your needs, mine in
// bare-bones is about 5, with full chassis must be higher
setSpeed(abs(speed) * 5);
}
// do turns
void doturn(int t) {
/** turn only in possible directions **/
int lPos = checkLimit();
// hit right and commanded right, not possible
if (lPos == 1 and t > 0) return;
// hit left and commanded left, not possible
if (lPos == -1 and t < 0) return;
// middle position, do move to either way
turn = t;
dirMot.steps(turn);
}
// receive data from the remote control unit
void rxCommand() {
// data will be set into a buffer and process flag will be rised
// receive radio data
while (_radio.hasData()) {
// Note how '&' must be placed in front of the variable name.
_radio.readData(&_radioData);
// reset the serial
pktSerial = _radioData.serial;
/**** priority commands first and will exit the loop ****/
// Stop
if (_radioData.stop) {
// stop motor
motionStop();
// exit loop
break;
}
/**** normal commands ****/
// look ahead
if (_radioData.lookAhead) {
// call the procedure tolookahead
dirTofont();
// exit loop
break;
}
// set speed to this
if (_radioData.speed != 0) {
// calc speed
speed += _radioData.speed;
// check limits
if (speed < -255) speed = -255;
if (speed > 255) speed = 255;
// which direction
if (speed > 0) {
// forward
setDirection(0);
} else {
// reverse
setDirection(1);
}
// set speed
setSpeed(speed);
}
// set turn direction
if (_radioData.turn != 0) {
// doturn
doturn(_radioData.turn);
}
// set options to this
//~ setOptions(_radioData.options);
// DEBUG
#ifdef SDEBUG
Serial.println(speed);
Serial.println(direction);
#endif
}
}
// check direction limit switches
char checkLimit() {
// measure value
int ana = analogRead(dirLimitPin);
// check limits
if (ana < 200) return -1; // left
if (ana > 823) return 1; // right
// if not in range just return zero
return 0;
}
// Move direction to the front position
void dirTofont() {
// check if we are already looking forward
if (digitalRead(dirHall) == 0) return;
// local var to set the direction
int steps = 500;
if (turn > 0) steps = -500;
// move
doturn(steps);
// move to center
while(!center) {
// motor move
dirMot.check();
// check limit hit
if (checkLimit() > 0) {
// right limit hit, move left
doturn(-500);
}
// check limit hit
if (checkLimit() < 0) {
// left limit hit, move right
doturn(500);
}
}
// reset the center flag
dirMot.stop();
center = false;
// once done reset turn to center
turn = 0;
}
// shift out the motor data for the direction
void dirShiftOut(byte dat) {
// move the bits to the upper four and mask it with the shiftOptions
dat = dat << 4;
shiftOptions = (shiftOptions & B00001111) + dat;
// shift it out
shiftOut();
}
// shift the motor and options out
void shiftOut() {
// pull the CS low
digitalWrite(dirLatch, LOW);
// push it
SPI.transfer(shiftOptions);
// pull the CS high
digitalWrite(dirLatch, HIGH);
}
/************************************************************************/
void setup () {
// serial console
#ifdef SDEBUG
Serial.begin(9600);
#endif
// init the NRF radio
/*****
* By default, 'init' configures the radio to use a 2MBPS bitrate
* on channel 100 (channels 0-125 are valid).
*
* Both the RX and TX radios must have the same bitrate and
* channel to communicate with each other.
*
* You can assign a different bitrate and channel as shown
* below.
*
* _radio.init(RADIO_ID, PIN_RADIO_CE, PIN_RADIO_CSN,
* NRFLite::BITRATE250KBPS, 0)
* _radio.init(RADIO_ID, PIN_RADIO_CE, PIN_RADIO_CSN,
* NRFLite::BITRATE1MBPS, 75)
* _radio.init(RADIO_ID, PIN_RADIO_CE, PIN_RADIO_CSN,
* NRFLite::BITRATE2MBPS, 100)
*******/
if (!_radio.init(RADIO_ID, PIN_RADIO_CE, PIN_RADIO_CSN, NRFLite::BITRATE250KBPS, 52)) {
#ifdef SDEBUG
Serial.println("Cannot communicate with radio");
#endif
while (1); // Wait here forever.
}
// Radio initialized ok
#ifdef SDEBUG
Serial.println("Radio init done.");
#endif
// direction motor
pinMode(dirLatch, OUTPUT);
digitalWrite(dirLatch, HIGH);
// set call back function
dirMot.addCallBack(dirShiftOut);
// set speed in steps per one second (1000 Max)
dirMot.speed(80);
// set steps per turn
dirMot.stepsPerTurn = 200;
// set eco mode, just power during the move, on idle poweroff
dirMot.eco = true;
// hal sensor setup (FALLING, it's normally high)
pinMode(dirHall, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(dirHall), centerHit, FALLING);
// delay to allow for settling.
delay(500);
// face fwd
dirTofont();
// set pins related to FWD/REV and speed
pinMode(motorSpeedPin, OUTPUT);
pinMode(motorDirectionPin, OUTPUT);
}
void loop () {
// Every 500 miliseconds, do a measurement using the sensor and print the distance in centimeters.
//~ #ifdef SDEBUG
//~ Serial.println(distanceSensor.measureDistanceCm());
//~ #endif
//~ delay(500);
// receive data from remote control
rxCommand();
// check async to do the move
dirMot.check();
}