forked from cgwood/ArdustationMega
-
Notifications
You must be signed in to change notification settings - Fork 0
/
pagesRover.ino
534 lines (473 loc) · 12.7 KB
/
pagesRover.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
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
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
/*
* pagesRover.ino
*
* Created on: 20 Oct 2013
* Author: Colin
*/
////////////////////////////////////////////////////////////////////////////////
// Parameters page
////////////////////////////////////////////////////////////////////////////////
PageRoverParameters::PageRoverParameters() {
uint8_t i;
/// Copy the header and types to internal storage
// _textHeader = ParamNamesRover;
_scale = (uint8_t*) ParamScalesRover;
_decPos = (uint8_t*) ParamDPsRover;
_paramCount = PARAM_COUNT_ROVER;
// Set the parameter IDs - requires parameter IDs to be consecutive (later something more robust?)
for (i = 0; i < _paramCount; i++) {
_Types[i] = i;
}
/// Initially, no values are available
for (i = 0; i < _paramCount; i++) {
_avail[i] = 1;
}
// Ensure we're at the top of the page not editing anything to start with
_state = 0;
_stateFirstVal = 0;
}
uint8_t PageRoverParameters::_enter(void) {
_drawLocal();
}
uint8_t PageRoverParameters::_forceUpdate(uint8_t reason) {
if (reason == R_PARAM) {
// Exit edit mode
_state = 0;
// Redraw the entire page
_drawLocal();
}
return 0;
}
uint8_t PageRoverParameters::_redefine(void) {
}
uint8_t PageRoverParameters::_refresh_med() {
return 0;
}
uint8_t PageRoverParameters::_refresh_slow() {
return 0;
}
void PageRoverParameters::_drawLocal(void) {
uint8_t c;
uint8_t i;
uint8_t j;
uint8_t k;
uint8_t lineno;
char decBuf[20 - PARAMNAMEFIELDWIDTH];
uint32_t value;
float value_local;
lcd.ClearArea();
// Write the value names down the left hand side
i = 0;
for (j = 0; j < _stateFirstVal + LINECOUNT; j++) { //Need to go from zero to read through the string
// If there are less parameters than available lines, quit at end of list
if (j >= _paramCount)
break;
if (j >= _stateFirstVal)
lcd.CursorTo(0, j - _stateFirstVal);
k = 0;
for (;;) {
// c = pgm_read_byte_near(_textHeader + i++);
if (uav.type == MAV_TYPE_FIXED_WING) {
c = pgm_read_byte_near(ParamNamesRover + i++);
} else if (uav.type == MAV_TYPE_GROUND_ROVER) {
c = pgm_read_byte_near(ParamNamesRover + i++);
} else {
c = pgm_read_byte_near(ParamNamesRover + i++);
}
if (0 == c)
break;
if ('\n' == c)
break;
else {
if (j >= _stateFirstVal && k++ < PARAMNAMEFIELDWIDTH)
lcd.write(c);
}
}
}
// Write the values
for (lineno = 0; lineno < LINECOUNT; lineno++) {
lcd.CursorTo(PARAMNAMEFIELDWIDTH + 2, lineno);
i = _stateFirstVal + lineno;
if (i >= _paramCount)
break;
// if (_avail[i] == 1) {
if (uav.param_rover_avail[i] == 1) {
// Load the value, either editing or live val
if (i == (_state - 101))
value = _value_temp;
else {
j = _Types[i];
//nvram.load_param(&j,&value_local);
value_local = uav.param_rover[j];
value = (uint32_t) floor(value_local + 0.5);
}
//value = _value_live[i].value;
// Is it an On / Off value?
if (99 == _decPos[i] && 99 == _scale[i]) {
if (value > 0) {
decBuf[0] = 'N';
decBuf[1] = 'O';
j = 2;
} else {
decBuf[0] = 'F';
decBuf[1] = 'F';
decBuf[2] = 'O';
j = 3;
}
// Display the data
//lcd.write(' ');
while (j-- > 0)
lcd.write(decBuf[j]);
lcd.write(' ');
} else {
GLCD.CursorTo(PARAMNAMEFIELDWIDTH + 2, lineno);
GLCD.print(value_local * pow(10, -_scale[i]), _decPos[i]);
GLCD.print(" ");
// // Scale the value and fix for the number of decimal places
// value *= pow(10,_decPos[i] - _scale[i]);
// decBuf[0] = '0' + (value % 10);
// value /= 10;
// for (j=1;j<(16-PARAMNAMEFIELDWIDTH);j++) {
// if (j == _decPos[i]) {
// decBuf[j] = '.';
// } else if ((0 == value) && (j > (_decPos[i] + 1))) {
// decBuf[j] = ' ';
// } else {
// decBuf[j] = '0' + (value % 10);
// value /= 10;
// }
// }
}
} else {
// Data unavailable, display dashes
for (j = 0; j < 16 - PARAMNAMEFIELDWIDTH; j++)
decBuf[j] = '-';
// Display the data
lcd.write(' ');
while (j-- > 0)
lcd.write(decBuf[j]);
lcd.write(' ');
}
}
// redraw the "choosing" marker
// _paintMarker();
}
/// Draw the "choosing" marker
void PageRoverParameters::_paintMarker(void) {
if (_state > 0 && _state < 100) {
lcd.CursorTo(PARAMNAMEFIELDWIDTH, _state - 1 - _stateFirstVal);
lcd.write('>');
} else if (_state > 100 && _state < 200) {
lcd.CursorTo(PARAMNAMEFIELDWIDTH, _state - 101 - _stateFirstVal);
lcd.write('#');
}
}
/// remove the "choosing" marker
void PageRoverParameters::_clearMarker(void) {
if (_state > 0 && _state < 200) {
if (_state > 100)
lcd.CursorTo(PARAMNAMEFIELDWIDTH, _state - 101 - _stateFirstVal);
else
lcd.CursorTo(PARAMNAMEFIELDWIDTH, _state - 1 - _stateFirstVal);
lcd.write(' ');
}
}
void PageRoverParameters::_alterLocal(float alterMag) {
// Is it an on off?
// if (99 == _scale[_state-101] && 99 == _decPos[_state-101]) {
// Serial.println(alterMag, DEC);
// if (alterMag > 0) {
// switch (_value_temp) {
// case 0x50: _value_temp = LOGBIT_ATTITUDE_FAST; break;
// case 0x51: _value_temp = LOGBIT_ATTITUDE_MED; break;
// case 0x52: _value_temp = LOGBIT_GPS; break;
// case 0x53: _value_temp = LOGBIT_PM; break;
// case 0x54: _value_temp = LOGBIT_CTUN; break;
// case 0x55: _value_temp = LOGBIT_NTUN; break;
// case 0x56: _value_temp = LOGBIT_MODE; break;
// case 0x57: _value_temp = LOGBIT_RAW; break;
// case 0x58: _value_temp = LOGBIT_CMD; break;
// }
// }
// else
// _value_temp = 0;
// }
// else {
// We don't do negative values here
if (_value_temp + alterMag < 0)
_value_temp = 0;
else
_value_temp += alterMag;
// }
// Keep the encoder value updated
if (_scale[_state - 101] == 99 && 99 == _decPos[_state - 101]) {
_value_encoder = (int) (_value_temp);
} else {
_value_encoder = (int) (_value_temp
/ (pow(10, _scale[_state - 101] - _decPos[_state - 101]))); // * 100;
}
// Serial.println(_value_temp);
// kick the update function
_updated = true;
}
void PageRoverParameters::_redrawLocal(void) {
// uint8_t c;
uint8_t i;
uint8_t j;
// uint8_t lineno;
char decBuf[PIDFIELDWIDTH];
uint32_t value;
float value_local;
uint8_t lineno;
// Check that the state is not in confirmation mode and a value is being pointed at
if (_state < 200 && _state > 0) {
if (_state > 100) {
value_local = _value_temp;
i = _state - 101;
} else {
i = _state - 1;
}
// Write the value
lineno = i - _stateFirstVal;
GLCD.CursorTo(PARAMNAMEFIELDWIDTH + 2, lineno);
// Is it an On / Off value?
if (99 == _decPos[i] && 99 == _scale[i]) {
if (value_local > 0) {
GLCD.print("ON ");
} else {
GLCD.print("OFF");
}
} else {
GLCD.print(value_local * pow(10, -_scale[i]), _decPos[i]);
GLCD.print(" ");
}
// value = (uint32_t)(floor(value_local+0.5));
// value *= pow(10,_decPos[i] - _scale[i]);
// Serial.println(value);
// decBuf[0] = '0' + (value % 10);
// value /= 10;
// for (j=1;j<(16-PARAMNAMEFIELDWIDTH);j++) {
// if (j == _decPos[i]) {
// decBuf[j] = '.';
// } else if ((0 == value) && (j > (_decPos[i] + 1))) {
// decBuf[j] = ' ';
// } else {
// decBuf[j] = '0' + (value % 10);
// value /= 10;
// }
// }
//
// // Display the data
// while (j-- > 0)
// lcd.write(decBuf[j]);
}
}
void PageRoverParameters::_voidLocal(void) {
// Reset the variable and redraw
int j = _Types[(_state % 100) - 1];
_value_temp = uav.param_rover[j];
_redrawLocal();
// Reset _state
_state = 0;
// Will also have to redraw the value to its original
// kick the update function
_updated = true;
}
void PageRoverParameters::_uploadConfirm(void) {
uint8_t c;
uint8_t row;
const prog_char *str;
str = confirmMessage;
lcd.ClearArea();
row = 0;
for (;;) {
c = pgm_read_byte_near(str++);
if (0 == c)
break;
if ('\n' == c) {
lcd.CursorTo(0, ++row);
continue;
}
// emit
lcd.write(c);
}
}
void PageRoverParameters::_uploadLocal(void) {
uint8_t i,j;
char str_param_id[16];
// Send the value that we edited
j = _Types[_state - 201];
// First initialise the string to be empty
for (i=0;i<15;i++)
str_param_id[i] = 0;
// Copy the relevant one into memory
strcpy_P(str_param_id, (char*)pgm_read_word(&(paramTable_rover[j])));
// Upload the value
gcs3.param_set(j, _value_temp, str_param_id);
// Reset _state
_state = 0;
// kick the update function
_updated = true;
}
uint8_t PageRoverParameters::_interact(uint8_t buttonid) {
_clearMarker();
switch (buttonid) {
case B_UP:
// Navigation
if (_state == 0) {
if (_stateFirstVal > 0) {
_stateFirstVal--;
_drawLocal();
}
} else if (_state > 1 && _state < 100) {
if (_state == (_stateFirstVal + 1)) {
_stateFirstVal--;
_drawLocal();
}
_state--;
}
// Editing
else if (_state > 100 && _state < 200) {
if (_scale[_state - 101] == 99 && 99 == _decPos[_state - 101]) {
if (_value_temp == 0)
_alterLocal(1);
} else {
_alterLocal(1 * pow(10, _scale[_state - 101] - _decPos[_state - 101]));
}
_redrawLocal();
}
// Confirming
else if (_state > 200)
return 0;
break;
case B_DOWN:
// Navigation
if (_state == 0) {
if (_stateFirstVal < _paramCount - LINECOUNT) {
_stateFirstVal++;
_drawLocal();
}
} else if (_state > 0 && _state < _paramCount) {
if (_state == (_stateFirstVal + LINECOUNT)) {
_stateFirstVal++;
_drawLocal();
}
_state++;
}
// Editing
else if (_state > 100 && _state < 200) {
if (_scale[_state - 101] == 99 && 99 == _decPos[_state - 101]) {
if (_value_temp == 1)
_alterLocal(-1);
} else {
_alterLocal(-1 * pow(10, _scale[_state - 101] - _decPos[_state - 101]));
}
_redrawLocal();
}
// Confirming
else if (_state > 200)
return 0;
break;
case B_OK:
if (_state == 0) {
// Allow selection if the value is available
if (_avail[_stateFirstVal])
_state = _stateFirstVal + 1;
} else if (_state < 100) {
// Allow editing if the value is available
if (_avail[(_state - 1)]) {
uint8_t j;
j = _Types[_state - 1];
//nvram.load_param(&j,&_value_temp);
_value_temp = uav.param_rover[j];
// Configure the encoder
if (_scale[_state - 1] == 99 && 99 == _decPos[_state - 1]) {
_value_encoder = (int) (_value_temp);
rotary.configure(&_value_encoder, 1, 0, -4);
} else {
_value_encoder =
(int) (_value_temp
/ (pow(10,
_scale[_state - 1]
- _decPos[_state - 1]))); // * 100;
rotary.configure(&_value_encoder, 1000, 0, -4);
}
// Copy the value to temp for editing
// memcpy(&_value_temp, _value_live[_state-1], sizeof(_value_temp));
//_value_temp.valueID = _value_live[_state-1].valueID;
//_value_temp.value = _value_live[_state-1].value;
// Update the state
_state += 100;
}
} else if (_state > 100 && _state < 200) {
// Save the value
//_leave(OK);
_state += 100;
_uploadConfirm();
return 0; // Leave before we draw the marker again
} else if (_state > 200) {
// Save the value
//_leave(OK);
_uploadLocal();
return 0; // Leave before we draw the marker again
}
break;
case B_LEFT:
// Navigation
if (_state == 0)
Pages::move(-1);
// Editing
else if (_state > 100 && _state < 200
&& !(_scale[_state - 101] == 99 && 99 == _decPos[_state - 101])) {
_alterLocal(-10 * pow(10, _scale[_state - 101] - _decPos[_state - 101]));
_redrawLocal();
}
// Confirming
else if (_state > 200)
return 0;
break;
case B_RIGHT:
// Navigation
if (_state == 0)
Pages::move(1);
// Editing
else if (_state > 100 && _state < 200
&& !(_scale[_state - 101] == 99 && 99 == _decPos[_state - 101])) {
_alterLocal(10 * pow(10, _scale[_state - 101] - _decPos[_state - 101]));
_redrawLocal();
}
// Confirming
else if (_state > 200)
return 0;
break;
case B_CANCEL:
if (_state == 0) {
Pages::move(0);
return 0; // avoid drawing the cursor
} else {
if (_state > 200) {
_drawLocal();
_state = 0;
} else if (_state > 100)
// Don't save the changes to local variable
_voidLocal();
else
_state = 0;
}
break;
case B_ENCODER:
if (_state > 100 && _state < 200) {
if (_scale[_state - 101] == 99 && 99 == _decPos[_state - 101]) {
_value_temp = _value_encoder;
} else {
_value_temp = _value_encoder
* pow(10, _scale[_state - 101] - _decPos[_state - 101]);
}
_redrawLocal();
// Serial.println(_value_encoder);
// Serial.println(_value_temp);
}
break;
}
_paintMarker();
}