/
main.c
504 lines (400 loc) · 13.8 KB
/
main.c
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
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
/*
* main.c
*/
// standard libs
#include <avr/io.h>
#include <avr/interrupt.h>
#include <math.h>
#include <inttypes.h>
#include <util/delay.h>
#include "main.h"
#include "LCD_driver.h"
#include "button.h"
#include "bbot_util.h"
#include "tilt.h"
#include "parameters.h"
#include "avrlibtypes.h"
#include "uart.h"
#include "vt100.h"
#include "rprintf.h"
// Motor control circuit is connected to PortB
// +---+---+---+---+---+
// Port B | 1 | 3 | 5 | 7 | V |
// Motor Control pins +---+---+---+---+---+
// | 0 | 2 | 4 | 6 | G |
// +---+---+---+---+---+
//
// PB2 - Left Motor FWD/REV Yellow
// PB3 - Right Motor FWD/REV Blue
// PB5 - Right Motor PWM Blue/Black
// PB6 - Left Motor PWM Yellow/Black
//
//
// Analog sensors can be connected to Port F ADC4(PF4) thru ADC7(PF7). By default Port F
// is used for JTAG and such JTAG functionality must be disabled.
// The pins are NOT numbered the same as the other connectors.
//
// +---+---+---+---+---+
// Port F (JTAG) | x | x | x | x | x | Pins marked with "x" should not be used.
// Usable Pins +---+---+---+---+---+
// | 7 | x | 5 | 6 | 4 |
// +---+---+---+---+---+
#define gyro_sensor 4
#define accel_sensor 5
// ADC (Built in 10 bit 0-5V) Information.
// Each ADC unit equals: 5.0V / 1024 = 0.004882812 V = 4.8828125 mV
//
// Rate Gyro (ADXRS401) Information:
// Rate Gyro measures rate at 15 mV/degree/second
// Each ADC Gyro unit equals: 4.8828125 / 15.0 = 0.325520833 degrees/sec
//
// Acceleromter (ADXL203) Information:
// Accelerometer measures acceleration at 1000 mV/g
// Each ADC unit equals: 4.8828125 / 1000mv/G = 0.0048828125 g
// Balance
double balance_torque;
double overspeed;
double overspeed_integral;
double gyro_integrated;
// PID Konstants
double Kp = 100; // balance loop P gain
double Ki = 50; // balance loop I gain
double Kd = 1; // balance loop D gain
//double Ksteer; // steering control gain
//double Ksteer2; // steering control tilt sensitivity
//double Kspeed; // speed tracking gain
double neutral = neutral_PARAM; // "angle of natural balance"
//double KpTurn; // turn rate loop P gain
//double KiTurn; // turn rate loop I gain
//double KdTurn; // turn rate loop D gain
// Outputs
int left_motor_torque;
int right_motor_torque;
volatile unsigned int accelRaw;
volatile unsigned int gyroRaw;
double current_angle = 0;
double current_rate = 0;
extern volatile char KEY_VALID;
// Variable from "button.c" to prevent button-bouncing
extern unsigned char gButtonTimeout;
int main (void)
{
Initialization();
show_mhz(); // Display CPU speed
TimerWait(1000); // Wait 1 second
while(1)
{
printLCD("Show ADC"); // Display the text in quotes on the LCD
while (!KEY_VALID); // Wait for joystick to be moved or pressed.
if (getkey() == 1) // If enter was pressed then do what is in the braces, just skip over it.
{
TimerWait(500); // debounce joystick button
showADC();
printLCD("Back ADCs");
TimerWait(2000);
}
printLCD("Balance"); // Display the text in quotes on the LCD
while (!KEY_VALID); // Wait for joystick to be moved or pressed.
if (getkey() == 1) // If enter was pressed then do what is in the braces, else just continue.
{
TimerWait(500); // debounce joystick button
balance();
printLCD("Back Balance");
TimerWait(2000);
}
printLCD("rprintf"); // Display the text in quotes on the LCD
while (!KEY_VALID); // Wait for joystick to be moved or pressed.
if (getkey() == 1) // If enter was pressed then do what is in the braces, else just continue.
{
TimerWait(500); // debounce joystick button
rprintf_test();
printLCD("Back rprintf");
TimerWait(2000);
}
printLCD("PWM Test"); // Display the text in quotes on the LCD
while (!KEY_VALID); // Wait for joystick to be moved or pressed.
if (getkey() == 1) // If enter was pressed then do what is in the braces, else just continue.
{
TimerWait(500); // debounce joystick button
PWM_Test();
printLCD("Back PWM Test");
TimerWait(3000);
}
}
}
/*****************************************************************************
* showADC - Displays ADC reading on the LCD display.
*****************************************************************************/
void showADC(void)
{
InitADC();
while (!(getkey() == 1))
{
gyroRaw = GetADC(gyro_sensor);
accelRaw = GetADC(accel_sensor);
TimerWait(100);
show12bits(gyroRaw, accelRaw);
}
LCD_ShowColons(0);
}
/*****************************************************************************
* Balance -
*****************************************************************************/
void balance(void)
{
unsigned long TimerMsWork;
long int g_bias = 0;
double x_offset = 532; //offset value 2.56V * 1024 / 4.93V = 4254
double q_m = 0.0;
double int_angle = 0.0;
double x = 0.0;
double tilt = 0.0;
int pwm;
InitADC();
init_pwm();
// initialize the UART (serial port)
uartInit();
// set the baud rate of the UART for our debug/reporting output
uartSetBaudRate(115200);
// initialize rprintf system
rprintfInit(uartSendByte);
// initialize vt100 library
vt100Init();
// clear the terminal screen
vt100ClearScreen();
TimerMsWork = TimerMsCur();
DDRB |= (1 << PB0); // Make B0 an output for LED
/* as a 1st step, a reference measurement of the angular rate sensor is
* done. This value is used as offset compensation */
for (int i=1 ; i<=200; i++) // determine initial value for bias of gyro
{
g_bias = g_bias + GetADC(gyro_sensor);
}
g_bias = g_bias / 200;
while (!(getkey() == 1))
{
/* insure loop runs at specified Hz */
while (!TimerCheck(TimerMsWork, (dt_PARAM * 1000) -1))
;
TimerMsWork = TimerMsCur();
// toggle pin B0 for oscilloscope timings.
PORTB = PINB ^ (1 << PB0);
// get rate gyro reading and convert to deg/sec
// q_m = (GetADC(gyro_sensor) - g_bias) / -3.072; // -3.07bits/deg/sec (neg. because forward is CCW)
q_m = (GetADC(gyro_sensor) - g_bias) * -0.3255; // each bit = 0.3255 /deg/sec (neg. because forward is CCW)
state_update(q_m);
// get Accelerometer reading and convert to units of gravity.
// x = (GetADC(accel_sensor) - x_offset) / 204.9; // (205 bits/G)
x = (GetADC(accel_sensor) - x_offset) * 0.00488; // each bit = 0.00488/G
// x is measured in multiples of earth gravitation g
// therefore x = sin (tilt) or tilt = arcsin(x)
// for small angles in rad (not deg): arcsin(x)=x
// Calculation of deg from rad: 1 deg = 180/pi = 57.29577951
tilt = 57.29577951 * (x);
kalman_update(tilt);
int_angle += angle * dt_PARAM;
rprintf(" x:");
rprintfFloat(8, x);
rprintf(" angle:");
rprintfFloat(8, angle);
rprintf(" rate:");
rprintfFloat(8, rate);
// Balance. The most important line in the entire program.
// balance_torque = Kp * (current_angle - neutral) + Kd * current_rate;
// rprintf("bal_torq: ");
// rprintfFloat(8, balance_torque);
// rprintfCRLF();
//steer_knob = 0;
// change from current angle to something proportional to speed
// should this be the abs val of the cur speed or just curr speed?
//double steer_cmd = (1.0 / (1.0 + Ksteer2 * fabs(current_angle))) * (Ksteer * steer_knob);
//double steer_cmd = 0.0;
// Get current rate of turn
//double current_turn = left_speed - right_speed; //<-- is this correct
//double turn_accel = current_turn - prev_turn;
//prev_turn = current_turn;
// Closed-loop turn rate PID
//double steer_cmd = KpTurn * (current_turn - steer_desired)
// + KdTurn * turn_accel;
// //+ KiTurn * turn_integrated;
// Possibly optional
//turn_integrated += current_turn - steer_cmd;
// Differential steering
//left_motor_torque = balance_torque + steer_cmd; //+ cur_speed + steer_cmd;
//right_motor_torque = balance_torque - steer_cmd; //+ cur_speed - steer_cmd;
// Limit extents of torque demand
//left_motor_torque = flim(left_motor_torque, -MAX_TORQUE, MAX_TORQUE);
// if (left_motor_torque < -MAX_TORQUE) left_motor_torque = -MAX_TORQUE;
// if (left_motor_torque > MAX_TORQUE) left_motor_torque = MAX_TORQUE;
//right_motor_torque = flim(right_motor_torque, -MAX_TORQUE, MAX_TORQUE);
// if (right_motor_torque < -MAX_TORQUE) right_motor_torque = -MAX_TORQUE;
// if (right_motor_torque > MAX_TORQUE) right_motor_torque = MAX_TORQUE;
pwm = (int) ((angle -3.5) * Kp) + (rate * Kd); // + (int_angle * Ki);
rprintf(" pwm:%d\r\n", pwm);
// Set PWM values for both motors
SetLeftMotorPWM(pwm);
SetRightMotorPWM(pwm);
}
SetLeftMotorPWM(0);
SetRightMotorPWM(0);
}
/*******************************************************************
* rprintf_test
*******************************************************************/
void rprintf_test(void)
{
u16 val;
u08 mydata;
u08 mystring[10];
double b;
u08 small;
u16 medium;
u32 big;
// initialize the UART (serial port)
uartInit();
// set the baud rate of the UART for our debug/reporting output
uartSetBaudRate(38400);
// initialize rprintf system
// - use uartSendByte as the output for all rprintf statements
// this will cause all rprintf library functions to direct their
// output to the uart
// - rprintf can be made to output to any device which takes characters.
// You must write a function which takes an unsigned char as an argument
// and then pass this to rprintfInit like this: rprintfInit(YOUR_FUNCTION);
rprintfInit(uartSendByte);
// initialize vt100 library
vt100Init();
// clear the terminal screen
vt100ClearScreen();
while (!(getkey() == 1)) //do the folling block until enter is pressed
{
// print a little intro message so we know things are working
rprintf("\r\nWelcome to rprintf Test!\r\n");
// print single characters
rprintfChar('H');
rprintfChar('e');
rprintfChar('l');
rprintfChar('l');
rprintfChar('o');
// print a constant string stored in FLASH
rprintfProgStrM(" World!");
// print a carriage return, line feed combination
rprintfCRLF();
// note that using rprintfCRLF() is more memory-efficient than
// using rprintf("\r\n"), especially if you do it repeatedly
mystring[0] = 'A';
mystring[1] = ' ';
mystring[2] = 'S';
mystring[3] = 't';
mystring[4] = 'r';
mystring[5] = 'i';
mystring[6] = 'n';
mystring[7] = 'g';
mystring[8] = '!';
mystring[9] = 0; // null termination
// print a null-terminated string from RAM
rprintfStr(mystring);
rprintfCRLF();
// print a section of a string from RAM
// - start at index 2
// - print 6 characters
rprintfStrLen(mystring, 2, 6);
rprintfCRLF();
val = 24060;
mydata = 'L';
// print a decimal number
rprintf("This is a decimal number: %d\r\n", val);
// print a hex number
rprintf("This is a hex number: %x\r\n", mydata);
// print a character
rprintf("This is a character: %c\r\n", mydata);
// print hex numbers
small = 0x12; // a char
medium = 0x1234; // a short
big = 0x12345678; // a long
rprintf("This is a 2-digit hex number (char) : ");
rprintfu08(small);
rprintfCRLF();
rprintf("This is a 4-digit hex number (short): ");
rprintfu16(medium);
rprintfCRLF();
rprintf("This is a 8-digit hex number (long) : ");
rprintfu32(big);
rprintfCRLF();
// print a formatted decimal number
// - use base 10
// - use 8 characters
// - the number is signed [TRUE]
// - pad with '.' periods
rprintf("This is a formatted decimal number: ");
rprintfNum(10, 8, TRUE, '.', val);
rprintfCRLF();
b = 1.23456;
// print a floating point number
// use 10-digit precision
// NOTE: TO USE rprintfFloat() YOU MUST ENABLE SUPPORT IN global.h
// use the following in your global.h: #define RPRINTF_FLOAT
rprintf("This is a floating point number: ");
rprintfFloat(8, b);
rprintfCRLF();
}
}
/*******************************************************
* PWM test - check wiring and such
*******************************************************/
void PWM_Test(void)
{
init_pwm();
while (!(getkey() == 1))
{
for (int i = 0; i <= 255 - lmb_PARAM; i++) {
show12bits(i, i);
SetLeftMotorPWM(i);
SetRightMotorPWM(i);
TimerWait(500);
}
for (int i = 0; i <= 255 - lmb_PARAM; i++) {
show12bits(i, i);
SetLeftMotorPWM(-i);
SetRightMotorPWM(-i);
TimerWait(500);
}
/*
printLCD("LFWD");
SetLeftMotorPWM(255);
SetRightMotorPWM(0);
TimerWait(3000);
printLCD("LREV");
SetLeftMotorPWM(-255);
SetRightMotorPWM(0);
TimerWait(3000);
printLCD("RFWD");
SetLeftMotorPWM(0);
SetRightMotorPWM(255);
TimerWait(3000);
printLCD("RREV");
SetLeftMotorPWM(0);
SetRightMotorPWM(-255);
TimerWait(3000);
printLCD("2 FWD low");
SetRightMotorPWM(128);
SetLeftMotorPWM(128);
TimerWait(3000);
printLCD("2 REV med");
SetRightMotorPWM(-200);
SetLeftMotorPWM(-200);
TimerWait(3000);
printLCD("CCW");
SetRightMotorPWM(200);
SetLeftMotorPWM(-200);
TimerWait(3000);
printLCD("CW");
SetRightMotorPWM(-200);
SetLeftMotorPWM(200);
TimerWait(3000);
*/
}
// Done
SetLeftMotorPWM(0);
SetRightMotorPWM(0);
}