-
Notifications
You must be signed in to change notification settings - Fork 34
/
_Phoenix_Code.h
2645 lines (2309 loc) · 98.5 KB
/
_Phoenix_Code.h
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
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
//Project Lynxmotion Phoenix
//Description: Phoenix software
//Software version: V2.0
//Date: 29-10-2009
//Programmer: Jeroen Janssen [aka Xan]
// Kurt Eckhardt(KurtE) converted to C and Arduino
// Kåre Halvorsen aka Zenta - Makes everything work correctly!
//
// This version of the Phoenix code was ported over to the Arduino Environement
// and is specifically configured for the Lynxmotion BotBoarduino
//
// Phoenix_Code.h
//
// This contains the main code for the Phoenix project. It is included in
// all of the different configurations of the phoenix code.
//
//NEW IN V2.X
//=============================================================================
//
//KNOWN BUGS:
// - Lots ;)
//
//=============================================================================
// Header Files
//=============================================================================
#define DEFINE_HEX_GLOBALS
#if ARDUINO>99
#include <Arduino.h>
#else
#endif
//#include <EEPROM.h>
//#include <PS2X_lib.h>
#include <pins_arduino.h>
//#include <SoftwareSerial.h>
#define BalanceDivFactor CNT_LEGS //;Other values than 6 can be used, testing...CAUTION!! At your own risk ;)
//#include <Wire.h>
//#include <I2CEEProm.h>
// Only compile in Debug code if we have something to output to
#ifdef DBGSerial
#define DEBUG
//#define DEBUG_X
#endif
//--------------------------------------------------------------------
//[TABLES]
//ArcCosinus Table
//Table build in to 3 part to get higher accuracy near cos = 1.
//The biggest error is near cos = 1 and has a biggest value of 3*0.012098rad = 0.521 deg.
//- Cos 0 to 0.9 is done by steps of 0.0079 rad. [1/127]
//- Cos 0.9 to 0.99 is done by steps of 0.0008 rad [0.1/127]
//- Cos 0.99 to 1 is done by step of 0.0002 rad [0.01/64]
//Since the tables are overlapping the full range of 127+127+64 is not necessary. Total bytes: 277
static const byte GetACos[] PROGMEM = {
255,254,252,251,250,249,247,246,245,243,242,241,240,238,237,236,234,233,232,231,229,228,227,225,
224,223,221,220,219,217,216,215,214,212,211,210,208,207,206,204,203,201,200,199,197,196,195,193,
192,190,189,188,186,185,183,182,181,179,178,176,175,173,172,170,169,167,166,164,163,161,160,158,
157,155,154,152,150,149,147,146,144,142,141,139,137,135,134,132,130,128,127,125,123,121,119,117,
115,113,111,109,107,105,103,101,98,96,94,92,89,87,84,81,79,76,73,73,73,72,72,72,71,71,71,70,70,
70,70,69,69,69,68,68,68,67,67,67,66,66,66,65,65,65,64,64,64,63,63,63,62,62,62,61,61,61,60,60,59,
59,59,58,58,58,57,57,57,56,56,55,55,55,54,54,53,53,53,52,52,51,51,51,50,50,49,49,48,48,47,47,47,
46,46,45,45,44,44,43,43,42,42,41,41,40,40,39,39,38,37,37,36,36,35,34,34,33,33,32,31,31,30,29,28,
28,27,26,25,24,23,23,23,23,22,22,22,22,21,21,21,21,20,20,20,19,19,19,19,18,18,18,17,17,17,17,16,
16,16,15,15,15,14,14,13,13,13,12,12,11,11,10,10,9,9,8,7,6,6,5,3,0 };//
//Sin table 90 deg, persision 0.5 deg [180 values]
static const word GetSin[] PROGMEM = {
0, 87, 174, 261, 348, 436, 523, 610, 697, 784, 871, 958, 1045, 1132, 1218, 1305, 1391, 1478, 1564,
1650, 1736, 1822, 1908, 1993, 2079, 2164, 2249, 2334, 2419, 2503, 2588, 2672, 2756, 2840, 2923, 3007,
3090, 3173, 3255, 3338, 3420, 3502, 3583, 3665, 3746, 3826, 3907, 3987, 4067, 4146, 4226, 4305, 4383,
4461, 4539, 4617, 4694, 4771, 4848, 4924, 4999, 5075, 5150, 5224, 5299, 5372, 5446, 5519, 5591, 5664,
5735, 5807, 5877, 5948, 6018, 6087, 6156, 6225, 6293, 6360, 6427, 6494, 6560, 6626, 6691, 6755, 6819,
6883, 6946, 7009, 7071, 7132, 7193, 7253, 7313, 7372, 7431, 7489, 7547, 7604, 7660, 7716, 7771, 7826,
7880, 7933, 7986, 8038, 8090, 8141, 8191, 8241, 8290, 8338, 8386, 8433, 8480, 8526, 8571, 8616, 8660,
8703, 8746, 8788, 8829, 8870, 8910, 8949, 8987, 9025, 9063, 9099, 9135, 9170, 9205, 9238, 9271, 9304,
9335, 9366, 9396, 9426, 9455, 9483, 9510, 9537, 9563, 9588, 9612, 9636, 9659, 9681, 9702, 9723, 9743,
9762, 9781, 9799, 9816, 9832, 9848, 9862, 9876, 9890, 9902, 9914, 9925, 9935, 9945, 9953, 9961, 9969,
9975, 9981, 9986, 9990, 9993, 9996, 9998, 9999, 10000 };//
//Build tables for Leg configuration like I/O and MIN/ Max values to easy access values using a FOR loop
//Constants are still defined as single values in the cfg file to make it easy to read/configure
// BUGBUG: Need a cleaner way to define...
// Lets allow for which legs servos to be inverted to be defined by the robot
// This is used by the Lynxmotion Symetrical Quad.
#ifndef cRRCoxaInv
#define cRRCoxaInv 1
#endif
#ifndef cRMCoxaInv
#define cRMCoxaInv 1
#endif
#ifndef cRFCoxaInv
#define cRFCoxaInv 1
#endif
#ifndef cLRCoxaInv
#define cLRCoxaInv 0
#endif
#ifndef cLMCoxaInv
#define cLMCoxaInv 0
#endif
#ifndef cLFCoxaInv
#define cLFCoxaInv 0
#endif
#ifndef cRRFemurInv
#define cRRFemurInv 1
#endif
#ifndef cRMFemurInv
#define cRMFemurInv 1
#endif
#ifndef cRFFemurInv
#define cRFFemurInv 1
#endif
#ifndef cLRFemurInv
#define cLRFemurInv 0
#endif
#ifndef cLMFemurInv
#define cLMFemurInv 0
#endif
#ifndef cLFFemurInv
#define cLFFemurInv 0
#endif
#ifndef cRRTibiaInv
#define cRRTibiaInv 1
#endif
#ifndef cRMTibiaInv
#define cRMTibiaInv 1
#endif
#ifndef cRFTibiaInv
#define cRFTibiaInv 1
#endif
#ifndef cLRTibiaInv
#define cLRTibiaInv 0
#endif
#ifndef cLMTibiaInv
#define cLMTibiaInv 0
#endif
#ifndef cLFTibiaInv
#define cLFTibiaInv 0
#endif
#ifndef cRRTarsInv
#define cRRTarsInv 1
#endif
#ifndef cRMTarsInv
#define cRMTarsInv 1
#endif
#ifndef cRFTarsInv
#define cRFTarsInv 1
#endif
#ifndef cLRTarsInv
#define cLRTarsInv 0
#endif
#ifndef cLMTarsInv
#define cLMTarsInv 0
#endif
#ifndef cLFTarsInv
#define cLFTarsInv 0
#endif
// Also define default BalanceDelay
#ifndef BALANCE_DELAY
#define BALANCE_DELAY 100
#endif
#ifdef HEXMODE
// Standard Hexapod...
// Servo Horn offsets
#ifdef cRRFemurHornOffset1 // per leg configuration
static const short cFemurHornOffset1[] PROGMEM = {
cRRFemurHornOffset1, cRMFemurHornOffset1, cRFFemurHornOffset1, cLRFemurHornOffset1, cLMFemurHornOffset1, cLFFemurHornOffset1};
#define CFEMURHORNOFFSET1(LEGI) ((short)pgm_read_word(&cFemurHornOffset1[LEGI]))
#else // Fixed per leg, if not defined 0
#ifndef cFemurHornOffset1
#define cFemurHornOffset1 0
#endif
#define CFEMURHORNOFFSET1(LEGI) (cFemurHornOffset1)
#endif
#ifdef cRRTibiaHornOffset1 // per leg configuration
static const short cTibiaHornOffset1[] PROGMEM = {
cRRTibiaHornOffset1, cRMTibiaHornOffset1, cRFTibiaHornOffset1, cLRTibiaHornOffset1, cLMTibiaHornOffset1, cLFTibiaHornOffset1};
#define CTIBIAHORNOFFSET1(LEGI) ((short)pgm_read_word(&cTibiaHornOffset1[LEGI]))
#else // Fixed per leg, if not defined 0
#ifndef cTibiaHornOffset1
#define cTibiaHornOffset1 0
#endif
#define CTIBIAHORNOFFSET1(LEGI) (cTibiaHornOffset1)
#endif
#ifdef c4DOF
#ifdef cRRTarsHornOffset1 // per leg configuration
static const short cTarsHornOffset1[] PROGMEM = {
cRRTarsHornOffset1, cRMTarsHornOffset1, cRFTarsHornOffset1, cLRTarsHornOffset1, cLMTarsHornOffset1, cLFTarsHornOffset1};
#define CTARSHORNOFFSET1(LEGI) ((short)pgm_read_word(&cTarsHornOffset1[LEGI]))
#else // Fixed per leg, if not defined 0
#ifndef cTarsHornOffset1
#define cTarsHornOffset1 0
#endif
#define CTARSHORNOFFSET1(LEGI) cTarsHornOffset1
#endif
#endif
//Min / Max values
#ifndef SERVOS_DO_MINMAX
const short cCoxaMin1[] PROGMEM = {
cRRCoxaMin1, cRMCoxaMin1, cRFCoxaMin1, cLRCoxaMin1, cLMCoxaMin1, cLFCoxaMin1};
const short cCoxaMax1[] PROGMEM = {
cRRCoxaMax1, cRMCoxaMax1, cRFCoxaMax1, cLRCoxaMax1, cLMCoxaMax1, cLFCoxaMax1};
const short cFemurMin1[] PROGMEM ={
cRRFemurMin1, cRMFemurMin1, cRFFemurMin1, cLRFemurMin1, cLMFemurMin1, cLFFemurMin1};
const short cFemurMax1[] PROGMEM ={
cRRFemurMax1, cRMFemurMax1, cRFFemurMax1, cLRFemurMax1, cLMFemurMax1, cLFFemurMax1};
const short cTibiaMin1[] PROGMEM ={
cRRTibiaMin1, cRMTibiaMin1, cRFTibiaMin1, cLRTibiaMin1, cLMTibiaMin1, cLFTibiaMin1};
const short cTibiaMax1[] PROGMEM = {
cRRTibiaMax1, cRMTibiaMax1, cRFTibiaMax1, cLRTibiaMax1, cLMTibiaMax1, cLFTibiaMax1};
#ifdef c4DOF
const short cTarsMin1[] PROGMEM = {
cRRTarsMin1, cRMTarsMin1, cRFTarsMin1, cLRTarsMin1, cLMTarsMin1, cLFTarsMin1};
const short cTarsMax1[] PROGMEM = {
cRRTarsMax1, cRMTarsMax1, cRFTarsMax1, cLRTarsMax1, cLMTarsMax1, cLFTarsMax1};
#endif
#endif
// Servo inverse direction
const bool cCoxaInv[] = {cRRCoxaInv, cRMCoxaInv, cRFCoxaInv, cLRCoxaInv, cLMCoxaInv, cLFCoxaInv};
bool cFemurInv[] = {cRRFemurInv, cRMFemurInv, cRFFemurInv, cLRFemurInv, cLMFemurInv, cLFFemurInv};
const bool cTibiaInv[] = {cRRTibiaInv, cRMTibiaInv, cRFTibiaInv, cLRTibiaInv, cLMTibiaInv, cLFTibiaInv};
#ifdef c4DOF
const boolean cTarsInv[] = {cRRTarsInv, cRMTarsInv, cRFTarsInv, cLRTarsInv, cLMTarsInv, cLFTarsInv};
#endif
//Leg Lengths
const byte cCoxaLength[] PROGMEM = {
cRRCoxaLength, cRMCoxaLength, cRFCoxaLength, cLRCoxaLength, cLMCoxaLength, cLFCoxaLength};
const byte cFemurLength[] PROGMEM = {
cRRFemurLength, cRMFemurLength, cRFFemurLength, cLRFemurLength, cLMFemurLength, cLFFemurLength};
const byte cTibiaLength[] PROGMEM = {
cRRTibiaLength, cRMTibiaLength, cRFTibiaLength, cLRTibiaLength, cLMTibiaLength, cLFTibiaLength};
#ifdef c4DOF
const byte cTarsLength[] PROGMEM = {
cRRTarsLength, cRMTarsLength, cRFTarsLength, cLRTarsLength, cLMTarsLength, cLFTarsLength};
#endif
//Body Offsets [distance between the center of the body and the center of the coxa]
const short cOffsetX[] PROGMEM = {
cRROffsetX, cRMOffsetX, cRFOffsetX, cLROffsetX, cLMOffsetX, cLFOffsetX};
const short cOffsetZ[] PROGMEM = {
cRROffsetZ, cRMOffsetZ, cRFOffsetZ, cLROffsetZ, cLMOffsetZ, cLFOffsetZ};
//Default leg angle
const short cCoxaAngle1[] PROGMEM = {
cRRCoxaAngle1, cRMCoxaAngle1, cRFCoxaAngle1, cLRCoxaAngle1, cLMCoxaAngle1, cLFCoxaAngle1};
#ifdef cRRInitCoxaAngle1 // We can set different angles for the legs than just where they servo horns are set...
const short cCoxaInitAngle1[] PROGMEM = {
cRRInitCoxaAngle1, cRMInitCoxaAngle1, cRFInitCoxaAngle1, cLRInitCoxaAngle1, cLMInitCoxaAngle1, cLFInitCoxaAngle1};
#endif
//Start positions for the leg
const short cInitPosX[] PROGMEM = {
cRRInitPosX, cRMInitPosX, cRFInitPosX, cLRInitPosX, cLMInitPosX, cLFInitPosX};
const short cInitPosY[] PROGMEM = {
cRRInitPosY, cRMInitPosY, cRFInitPosY, cLRInitPosY, cLMInitPosY, cLFInitPosY};
const short cInitPosZ[] PROGMEM = {
cRRInitPosZ, cRMInitPosZ, cRFInitPosZ, cLRInitPosZ, cLMInitPosZ, cLFInitPosZ};
//=============================================================================
#elif defined(OCTOMODE)
// Octopods
// Servo Horn offsets
#ifdef cRRFemurHornOffset1 // per leg configuration
static const short cFemurHornOffset1[] PROGMEM = {
cRRFemurHornOffset1, cRMRFemurHornOffset1, cRMFFemurHornOffset1, cRFFemurHornOffset1, cLRFemurHornOffset1, cLMRFemurHornOffset1, cLMFFemurHornOffset1, cLFFemurHornOffset1};
#define CFEMURHORNOFFSET1(LEGI) ((short)pgm_read_word(&cFemurHornOffset1[LEGI]))
#else // Fixed per leg, if not defined 0
#ifndef cFemurHornOffset1
#define cFemurHornOffset1 0
#endif
#define CFEMURHORNOFFSET1(LEGI) (cFemurHornOffset1)
#endif
#ifdef cRRTibiaHornOffset1 // per leg configuration
static const short cTibiaHornOffset1[] PROGMEM = {
cRRTibiaHornOffset1, cRMRTibiaHornOffset1, cRMFTibiaHornOffset1, cRFTibiaHornOffset1, cLRTibiaHornOffset1, cLMRTibiaHornOffset1, cLMFTibiaHornOffset1, cLFTibiaHornOffset1};
#define CTIBIAHORNOFFSET1(LEGI) ((short)pgm_read_word(&cTibiaHornOffset1[LEGI]))
#else // Fixed per leg, if not defined 0
#ifndef cTibiaHornOffset1
#define cTibiaHornOffset1 0
#endif
#define CTIBIAHORNOFFSET1(LEGI) (cTibiaHornOffset1)
#endif
#ifdef c4DOF
#ifdef cRRTarsHornOffset1 // per leg configuration
static const short cTarsHornOffset1[] PROGMEM = {
cRRTarsHornOffset1, cRMRTarsHornOffset1, cRMFTarsHornOffset1, cRFTarsHornOffset1, cLRTarsHornOffset1, cLMRTarsHornOffset1, cLMFTarsHornOffset1, cLFTarsHornOffset1};
#define CTARSHORNOFFSET1(LEGI) ((short)pgm_read_word(&cTarsHornOffset1[LEGI]))
#else // Fixed per leg, if not defined 0
#ifndef cTarsHornOffset1
#define cTarsHornOffset1 0
#endif
#define CTARSHORNOFFSET1(LEGI) cTarsHornOffset1
#endif
#endif
//Min / Max values
#ifndef SERVOS_DO_MINMAX
const short cCoxaMin1[] PROGMEM = {
cRRCoxaMin1, cRMRCoxaMin1, cRMFCoxaMin1, cRFCoxaMin1, cLRCoxaMin1, cLMRCoxaMin1, cLMFCoxaMin1, cLFCoxaMin1};
const short cCoxaMax1[] PROGMEM = {
cRRCoxaMax1, cRMRCoxaMax1, cRMFCoxaMax1, cRFCoxaMax1, cLRCoxaMax1, cLMRCoxaMax1, cLMFCoxaMax1, cLFCoxaMax1};
const short cFemurMin1[] PROGMEM ={
cRRFemurMin1, cRMRFemurMin1, cRMFFemurMin1, cRFFemurMin1, cLRFemurMin1, cLMRFemurMin1, cLMFFemurMin1, cLFFemurMin1};
const short cFemurMax1[] PROGMEM ={
cRRFemurMax1, cRMRFemurMax1, cRMFFemurMax1, cRFFemurMax1, cLRFemurMax1, cLMRFemurMax1, cLMFFemurMax1, cLFFemurMax1};
const short cTibiaMin1[] PROGMEM ={
cRRTibiaMin1, cRMRTibiaMin1, cRMFTibiaMin1, cRFTibiaMin1, cLRTibiaMin1, cLMRTibiaMin1, cLMFTibiaMin1, cLFTibiaMin1};
const short cTibiaMax1[] PROGMEM = {
cRRTibiaMax1, cRMRTibiaMax1, cRMFTibiaMax1, cRFTibiaMax1, cLRTibiaMax1, cLMRTibiaMax1, cLMFTibiaMax1, cLFTibiaMax1};
#ifdef c4DOF
const short cTarsMin1[] PROGMEM = {
cRRTarsMin1, cRMRTarsMin1, cRMFTarsMin1, cRFTarsMin1, cLRTarsMin1, cLMRTarsMin1, cLMFTarsMin1, cLFTarsMin1};
const short cTarsMax1[] PROGMEM = {
cRRTarsMax1, cRMRTarsMax1, cRMFTarsMax1, cRFTarsMax1, cLRTarsMax1, cLMRTarsMax1, cLMFTarsMax1, cLFTarsMax1};
#endif
#endif
// Servo inverse direction
const bool cCoxaInv[] = {cRRCoxaInv, cRMRCoxaInv, cRMFCoxaInv, cRFCoxaInv, cLRCoxaInv, cLMRCoxaInv, cLMFCoxaInv, cLFCoxaInv};
bool cFemurInv[] = {cRRFemurInv, cRMRFemurInv, cRMFFemurInv, cRFFemurInv, cLRFemurInv, cLMRFemurInv, cLMFFemurInv, cLFFemurInv};
const bool cTibiaInv[] = {cRRTibiaInv, cRMRTibiaInv, cRMFTibiaInv, cRFTibiaInv, cLRTibiaInv, cLMRTibiaInv, cLMFTibiaInv, cLFTibiaInv};
#ifdef c4DOF
const boolean cTarsInv[] = {cRRTarsInv, cRMRTarsInv, cRMFTarsInv, cRFTarsInv, cLRTarsInv, cLMRTarsInv, cLMFTarsInv, cLFTarsInv};
#endif
//Leg Lengths
const byte cCoxaLength[] PROGMEM = {
cRRCoxaLength, cRMRCoxaLength, cRMFCoxaLength, cRFCoxaLength, cLRCoxaLength, cLMRCoxaLength, cLMFCoxaLength, cLFCoxaLength};
const byte cFemurLength[] PROGMEM = {
cRRFemurLength, cRMRFemurLength, cRMFFemurLength, cRFFemurLength, cLRFemurLength, cLMRFemurLength, cLMFFemurLength, cLFFemurLength};
const byte cTibiaLength[] PROGMEM = {
cRRTibiaLength, cRMRTibiaLength, cRMFTibiaLength, cRFTibiaLength, cLRTibiaLength, cLMRTibiaLength, cLMFTibiaLength, cLFTibiaLength};
#ifdef c4DOF
const byte cTarsLength[] PROGMEM = {
cRRTarsLength, cRMRTarsLength, cRMFTarsLength, cRFTarsLength, cLRTarsLength, cLMRTarsLength, cLMFTarsLength, cLFTarsLength};
#endif
//Body Offsets [distance between the center of the body and the center of the coxa]
const short cOffsetX[] PROGMEM = {
cRROffsetX, cRMROffsetX, cRMFOffsetX, cRFOffsetX, cLROffsetX, cLMROffsetX, cLMFOffsetX, cLFOffsetX};
const short cOffsetZ[] PROGMEM = {
cRROffsetZ, cRMROffsetZ, cRMFOffsetZ, cRFOffsetZ, cLROffsetZ, cLMROffsetZ, cLMFOffsetZ, cLFOffsetZ};
//Default leg angle
const short cCoxaAngle1[] PROGMEM = {
cRRCoxaAngle1, cRMRCoxaAngle1, cRMFCoxaAngle1, cRFCoxaAngle1, cLRCoxaAngle1, cLMRCoxaAngle1, cLMFCoxaAngle1, cLFCoxaAngle1};
#ifdef cRRInitCoxaAngle1 // We can set different angles for the legs than just where they servo horns are set...
const short cCoxaInitAngle1[] PROGMEM = {
cRRInitCoxaAngle1, cRMRInitCoxaAngle1, cRMFInitCoxaAngle1, cRFInitCoxaAngle1, cLRInitCoxaAngle1, cLMRInitCoxaAngle1, cLMFInitCoxaAngle1, cLFInitCoxaAngle1};
#endif
//Start positions for the leg
const short cInitPosX[] PROGMEM = {
cRRInitPosX, cRMRInitPosX, cRMFInitPosX, cRFInitPosX, cLRInitPosX, cLMRInitPosX, cLMFInitPosX, cLFInitPosX};
const short cInitPosY[] PROGMEM = {
cRRInitPosY, cRMRInitPosY, cRMFInitPosY, cRFInitPosY, cLRInitPosY, cLMRInitPosY, cLMFInitPosY, cLFInitPosY};
const short cInitPosZ[] PROGMEM = {
cRRInitPosZ, cRMRInitPosZ, cRMFInitPosZ, cRFInitPosZ, cLRInitPosZ, cLMRInitPosZ, cLMFInitPosZ, cLFInitPosZ};
//=============================================================================
#else
// Quads...
// Servo Horn offsets
#ifdef cRRFemurHornOffset1 // per leg configuration
static const short cFemurHornOffset1[] PROGMEM = {
cRRFemurHornOffset1, cRFFemurHornOffset1, cLRFemurHornOffset1, cLFFemurHornOffset1};
#define CFEMURHORNOFFSET1(LEGI) ((short)pgm_read_word(&cFemurHornOffset1[LEGI]))
#else // Fixed per leg, if not defined 0
#ifndef cFemurHornOffset1
#define cFemurHornOffset1 0
#endif
#define CFEMURHORNOFFSET1(LEGI) (cFemurHornOffset1)
#endif
#ifdef cRRTibiaHornOffset1 // per leg configuration
static const short cTibiaHornOffset1[] PROGMEM = {
cRRTibiaHornOffset1, cRFTibiaHornOffset1, cLRTibiaHornOffset1, cLFTibiaHornOffset1};
#define CTIBIAHORNOFFSET1(LEGI) ((short)pgm_read_word(&cTibiaHornOffset1[LEGI]))
#else // Fixed per leg, if not defined 0
#ifndef cTibiaHornOffset1
#define cTibiaHornOffset1 0
#endif
#define CTIBIAHORNOFFSET1(LEGI) (cTibiaHornOffset1)
#endif
#ifdef c4DOF
#ifdef cRRTarsHornOffset1 // per leg configuration
static const short cTarsHornOffset1[] PROGMEM = {
cRRTarsHornOffset1, cRFTarsHornOffset1, cLRTarsHornOffset1, cLFTarsHornOffset1};
#define CTARSHORNOFFSET1(LEGI) ((short)pgm_read_word(&cTarsHornOffset1[LEGI]))
#else // Fixed per leg, if not defined 0
#ifndef cTarsHornOffset1
#define cTarsHornOffset1 0
#endif
#define CTARSHORNOFFSET1(LEGI) cTarsHornOffset1
#endif
#endif
//Min / Max values
#ifndef SERVOS_DO_MINMAX
const short cCoxaMin1[] PROGMEM = {
cRRCoxaMin1, cRFCoxaMin1, cLRCoxaMin1, cLFCoxaMin1};
const short cCoxaMax1[] PROGMEM = {
cRRCoxaMax1, cRFCoxaMax1, cLRCoxaMax1, cLFCoxaMax1};
const short cFemurMin1[] PROGMEM ={
cRRFemurMin1, cRFFemurMin1, cLRFemurMin1, cLFFemurMin1};
const short cFemurMax1[] PROGMEM ={
cRRFemurMax1, cRFFemurMax1, cLRFemurMax1, cLFFemurMax1};
const short cTibiaMin1[] PROGMEM ={
cRRTibiaMin1, cRFTibiaMin1, cLRTibiaMin1, cLFTibiaMin1};
const short cTibiaMax1[] PROGMEM = {
cRRTibiaMax1, cRFTibiaMax1, cLRTibiaMax1, cLFTibiaMax1};
#ifdef c4DOF
const short cTarsMin1[] PROGMEM = {
cRRTarsMin1, cRFTarsMin1, cLRTarsMin1, cLFTarsMin1};
const short cTarsMax1[] PROGMEM = {
cRRTarsMax1, cRFTarsMax1, cLRTarsMax1, cLFTarsMax1};
#endif
#endif
// Servo inverse direction
const bool cCoxaInv[] = {cRRCoxaInv, cRFCoxaInv, cLRCoxaInv, cLFCoxaInv};
bool cFemurInv[] = {cRRFemurInv, cRFFemurInv, cLRFemurInv, cLFFemurInv};
const bool cTibiaInv[] = {cRRTibiaInv, cRFTibiaInv, cLRTibiaInv, cLFTibiaInv};
#ifdef c4DOF
const boolean cTarsInv[] = {
cRRTarsInv, cRFTarsInv, cLRTarsInv, cLFTarsInv};
#endif
//Leg Lengths
const byte cCoxaLength[] PROGMEM = {
cRRCoxaLength, cRFCoxaLength, cLRCoxaLength, cLFCoxaLength};
const byte cFemurLength[] PROGMEM = {
cRRFemurLength, cRFFemurLength, cLRFemurLength, cLFFemurLength};
const byte cTibiaLength[] PROGMEM = {
cRRTibiaLength, cRFTibiaLength, cLRTibiaLength, cLFTibiaLength};
#ifdef c4DOF
const byte cTarsLength[] PROGMEM = {
cRRTarsLength, cRFTarsLength, cLRTarsLength, cLFTarsLength};
#endif
//Body Offsets [distance between the center of the body and the center of the coxa]
const short cOffsetX[] PROGMEM = {
cRROffsetX, cRFOffsetX, cLROffsetX, cLFOffsetX};
const short cOffsetZ[] PROGMEM = {
cRROffsetZ, cRFOffsetZ, cLROffsetZ, cLFOffsetZ};
//Default leg angle
const short cCoxaAngle1[] PROGMEM = {
cRRCoxaAngle1, cRFCoxaAngle1, cLRCoxaAngle1, cLFCoxaAngle1};
#ifdef cRRInitCoxaAngle1 // We can set different angles for the legs than just where they servo horns are set...
const short cCoxaInitAngle1[] PROGMEM = {
cRRInitCoxaAngle1, cRFInitCoxaAngle1, cLRInitCoxaAngle1, cLFInitCoxaAngle1};
#endif
//Start positions for the leg
const short cInitPosX[] PROGMEM = {
cRRInitPosX, cRFInitPosX, cLRInitPosX, cLFInitPosX};
const short cInitPosY[] PROGMEM = {
cRRInitPosY, cRFInitPosY, cLRInitPosY, cLFInitPosY};
const short cInitPosZ[] PROGMEM = {
cRRInitPosZ, cRFInitPosZ, cLRInitPosZ, cLFInitPosZ};
#endif
// Define some globals for debug information
boolean g_fShowDebugPrompt;
boolean g_fDebugOutput;
boolean g_fEnableServos = true;
//--------------------------------------------------------------------
//[REMOTE]
#ifndef cTravelDeadZone
#define cTravelDeadZone 4 //The deadzone for the analog input from the remote
#endif
//====================================================================
//[ANGLES]
short CoxaAngle1[CNT_LEGS]; //Actual Angle of the horizontal hip, decimals = 1
short FemurAngle1[CNT_LEGS]; //Actual Angle of the vertical hip, decimals = 1
short TibiaAngle1[CNT_LEGS]; //Actual Angle of the knee, decimals = 1
#ifdef c4DOF
short TarsAngle1[CNT_LEGS]; //Actual Angle of the knee, decimals = 1
#endif
//--------------------------------------------------------------------
//[POSITIONS SINGLE LEG CONTROL]
short LegPosX[CNT_LEGS]; //Actual X Posion of the Leg
short LegPosY[CNT_LEGS]; //Actual Y Posion of the Leg
short LegPosZ[CNT_LEGS]; //Actual Z Posion of the Leg
//--------------------------------------------------------------------
//[INPUTS]
//--------------------------------------------------------------------
//[GP PLAYER]
//--------------------------------------------------------------------
//[OUTPUTS]
boolean LedA; //Red
boolean LedB; //Green
boolean LedC; //Orange
boolean Eyes; //Eyes output
//--------------------------------------------------------------------
//[VARIABLES]
byte Index; //Index universal used
byte LegIndex; //Index used for leg Index Number
//GetSinCos / ArcCos
short AngleDeg1; //Input Angle in degrees, decimals = 1
short sin4; //Output Sinus of the given Angle, decimals = 4
short cos4; //Output Cosinus of the given Angle, decimals = 4
short AngleRad4; //Output Angle in radials, decimals = 4
//GetAtan2
short AtanX; //Input X
short AtanY; //Input Y
short Atan4; //ArcTan2 output
long XYhyp2; //Output presenting Hypotenuse of X and Y
//Body Inverse Kinematics
short PosX; //Input position of the feet X
short PosZ; //Input position of the feet Z
short PosY; //Input position of the feet Y
long BodyFKPosX; //Output Position X of feet with Rotation
long BodyFKPosY; //Output Position Y of feet with Rotation
long BodyFKPosZ; //Output Position Z of feet with Rotation
//Leg Inverse Kinematics
long IKFeetPosX; //Input position of the Feet X
long IKFeetPosY; //Input position of the Feet Y
long IKFeetPosZ; //Input Position of the Feet Z
boolean IKSolution; //Output true if the solution is possible
boolean IKSolutionWarning; //Output true if the solution is NEARLY possible
boolean IKSolutionError; //Output true if the solution is NOT possible
//--------------------------------------------------------------------
//[TIMING]
unsigned long lTimerStart; //Start time of the calculation cycles
unsigned long lTimerEnd; //End time of the calculation cycles
byte CycleTime; //Total Cycle time
word ServoMoveTime; //Time for servo updates
word PrevServoMoveTime; //Previous time for the servo updates
//--------------------------------------------------------------------
//[GLOABAL]
//--------------------------------------------------------------------
// Define our global Input Control State object
INCONTROLSTATE g_InControlState; // This is our global Input control state object...
// Define our ServoWriter class
ServoDriver g_ServoDriver; // our global servo driver class
boolean g_fLowVoltageShutdown; // If set the bot shuts down because the input voltage is to low
word Voltage;
//--boolean g_InControlState.fRobotOn; //Switch to turn on Phoenix
//--boolean g_InControlState.fPrev_RobotOn; //Previous loop state
//--------------------------------------------------------------------
//[Balance]
long TotalTransX;
long TotalTransZ;
long TotalTransY;
long TotalYBal1;
long TotalXBal1;
long TotalZBal1;
//[Single Leg Control]
boolean AllDown;
//[gait - State]
// Note: Information about the current gait is now part of the g_InControlState...
boolean TravelRequest; //Temp to check if the gait is in motion
long GaitPosX[CNT_LEGS]; //Array containing Relative X position corresponding to the Gait
long GaitPosY[CNT_LEGS]; //Array containing Relative Y position corresponding to the Gait
long GaitPosZ[CNT_LEGS]; //Array containing Relative Z position corresponding to the Gait
long GaitRotY[CNT_LEGS]; //Array containing Relative Y rotation corresponding to the Gait
//boolean GaitLegInAir[CNT_LEGS]; // True if leg is in the air
//byte GaitNextLeg; // The next leg which will be lifted
boolean fWalking; // True if the robot are walking
byte bExtraCycle; // Forcing some extra timed cycles for avoiding "end of gait bug"
#define cGPlimit 2 // GP=GaitPos testing different limits
boolean g_fRobotUpsideDown; // Is the robot upside down?
boolean fRobotUpsideDownPrev;
//=============================================================================
// Define our default standard Gaits
//=============================================================================
#ifndef DEFAULT_GAIT_SPEED
#define DEFAULT_GAIT_SPEED 50
#define DEFAULT_SLOW_GAIT 70
#endif
//cRR=0, cRF, cLR, cLF, CNT_LEGS};
#ifndef OVERWRITE_GAITS
#ifdef HEXMODE
// Hex Gaits
// Speed, Steps, Lifted, Front Down, Lifted Factor, Half Height, On Ground,
// Quad extra: COGAngleStart, COGAngleStep, CogRadius, COGCCW
// { RR, <RM> RF, LR, <LM>, LF}
#ifdef DISPLAY_GAIT_NAMES
extern "C" {
// Move the Gait Names to program space...
const char s_szGN1[] PROGMEM = "Ripple 12";
const char s_szGN2[] PROGMEM = "Tripod 8";
const char s_szGN3[] PROGMEM = "Tripple 12";
const char s_szGN4[] PROGMEM = "Tripple 16";
const char s_szGN5[] PROGMEM = "Wave 24";
const char s_szGN6[] PROGMEM = "Tripod 6";
};
#endif
PHOENIXGAIT APG[] = {
{DEFAULT_SLOW_GAIT, 12, 3, 2, 2, 8, 3, {7, 11, 3, 1, 5, 9} GATENAME(s_szGN1)}, // Ripple 12
{DEFAULT_SLOW_GAIT, 8, 3, 2, 2, 4, 3, {1, 5, 1, 5, 1, 5} GATENAME(s_szGN2)}, //Tripod 8 steps
{DEFAULT_GAIT_SPEED, 12, 3, 2, 2, 8, 3, {5, 10, 3, 11, 4, 9} GATENAME(s_szGN3) }, //Triple Tripod 12 step
{DEFAULT_GAIT_SPEED, 16, 5, 3, 4, 10, 1, {6, 13, 4, 14, 5, 12} GATENAME(s_szGN4)}, // Triple Tripod 16 steps, use 5 lifted positions
{DEFAULT_SLOW_GAIT, 24, 3, 2, 2, 20, 3, {13, 17, 21, 1, 5, 9} GATENAME(s_szGN5)}, //Wave 24 steps
{DEFAULT_GAIT_SPEED, 6, 2, 1, 2, 4, 1, {1, 4, 1, 4, 1, 4} GATENAME(s_szGN6)} //Tripod 6 steps
};
#elif defined(OCTOMODE)
// Octopod Gaits
// Speed, Steps, Lifted, Front Down, Lifted Factor, Half Height, On Ground,
// { RR, RMR, RMF, RF, LR, LMR, LMF, LF}
#ifdef DISPLAY_GAIT_NAMES
extern "C" {
// Move the Gait Names to program space...
const char s_szGN1[] PROGMEM = "Tripod 6";
};
#endif
PHOENIXGAIT APG[] = {
{DEFAULT_GAIT_SPEED, 6, 2, 1, 2, 4, 1, {1, 4, 1, 4, 4, 1, 4, 1} GATENAME(s_szGN1)} //Tripod 6 steps
};
#else
// Quad Gaits
#ifdef DISPLAY_GAIT_NAMES
extern "C" {
// Move the Gait Names to program space...
const char s_szGN1[] PROGMEM = "Ripple 12";
const char s_szGN2[] PROGMEM = "Tripod 8";
}
#endif
PHOENIXGAIT APG[] = {
{DEFAULT_GAIT_SPEED, 16, 3, 2, 2, 12, 3, 2250, 3600/16, 30, true, {5, 9, 1, 13} GATENAME(s_szGN1)}, // Wave 16
{1, 28, 3, 2, 2, 24, 3, 2250, 3600/28, 30, true, {8, 15, 1, 22} GATENAME(s_szGN2)} // Wave 28?
};
#endif
#endif
//--------------------------------------------------------------------
#ifdef ADD_GAITS
byte NUM_GAITS = sizeof(APG)/sizeof(APG[0]) + sizeof(APG_EXTRA)/sizeof(APG_EXTRA[0]);
#else
byte NUM_GAITS = sizeof(APG)/sizeof(APG[0]);
#endif
//=============================================================================
// Function prototypes
//=============================================================================
extern void GaitSelect(void);
extern void WriteOutputs(void);
extern void SingleLegControl(void);
extern void GaitSeq(void);
extern void BalanceBody(void);
extern void CheckAngles();
extern void PrintSystemStuff(void); // Try to see why we fault...
//extern void GaitGetNextLeg(byte GaitStep);
extern void BalCalcOneLeg (long PosX, long PosZ, long PosY, byte BalLegNr);
extern void BodyFK (short PosX, short PosZ, short PosY, short RotationY, byte BodyIKLeg) ;
extern void LegIK (short IKFeetPosX, short IKFeetPosY, short IKFeetPosZ, byte LegIKLegNr);
extern void Gait (byte GaitCurrentLegNr);
extern void GetSinCos(short AngleDeg1);
extern short GetATan2 (short AtanX, short AtanY);
extern unsigned long isqrt32 (unsigned long n);
extern void StartUpdateServos(void);
extern boolean TerminalMonitor(void);
//--------------------------------------------------------------------------
// SETUP: the main arduino setup function.
//--------------------------------------------------------------------------
void setup(){
#ifdef OPT_SKETCHSETUP
SketchSetup();
#endif
g_fShowDebugPrompt = true;
g_fDebugOutput = false;
#ifdef DBGSerial
DBGSerial.begin(38400);
#endif
// Init our ServoDriver
g_ServoDriver.Init();
//Checks to see if our Servo Driver support a GP Player
// DBGSerial.write("Program Start\n\r");
// debug stuff
delay(10);
//Turning off all the leds
LedA = 0;
LedB = 0;
LedC = 0;
Eyes = 0;
// Setup Init Positions
for (LegIndex= 0; LegIndex < CNT_LEGS; LegIndex++ )
{
LegPosX[LegIndex] = (short)pgm_read_word(&cInitPosX[LegIndex]); //Set start positions for each leg
LegPosY[LegIndex] = (short)pgm_read_word(&cInitPosY[LegIndex]);
LegPosZ[LegIndex] = (short)pgm_read_word(&cInitPosZ[LegIndex]);
}
ResetLegInitAngles();
//Single leg control. Make sure no leg is selected
#ifdef OPT_SINGLELEG
g_InControlState.SelectedLeg = 255; // No Leg selected
g_InControlState.PrevSelectedLeg = 255;
#endif
//Body Positions
g_InControlState.BodyPos.x = 0;
g_InControlState.BodyPos.y = 0;
g_InControlState.BodyPos.z = 0;
//Body Rotations
g_InControlState.BodyRot1.x = 0;
g_InControlState.BodyRot1.y = 0;
g_InControlState.BodyRot1.z = 0;
g_InControlState.BodyRotOffset.x = 0;
g_InControlState.BodyRotOffset.y = 0; //Input Y offset value to adjust centerpoint of rotation
g_InControlState.BodyRotOffset.z = 0;
//Gait
g_InControlState.GaitType = 0;
g_InControlState.BalanceMode = 0;
g_InControlState.LegLiftHeight = 50;
g_InControlState.ForceGaitStepCnt = 0; // added to try to adjust starting positions depending on height...
g_InControlState.GaitStep = 1;
GaitSelect();
#ifdef cTurretRotPin
g_InControlState.TurretRotAngle1 = cTurretRotInit; // Rotation of turrent in 10ths of degree
g_InControlState.TurretTiltAngle1 = cTurretTiltInit; // the tile for the turret
#endif
g_InputController.Init();
// Servo Driver
ServoMoveTime = 150;
g_InControlState.fRobotOn = 0;
g_fLowVoltageShutdown = false;
#ifdef DEBUG_IOPINS
// pinMode(A0, OUTPUT);
pinMode(A1, OUTPUT);
pinMode(A2, OUTPUT);
pinMode(A3, OUTPUT);
pinMode(A4, OUTPUT);
#endif
#ifdef OPT_WALK_UPSIDE_DOWN
g_fRobotUpsideDown = false; //Assume off...
#ifdef DBGSerial
DBGSerial.println(IsRobotUpsideDown, DEC);
#endif
#endif
}
//=============================================================================
// Loop: the main arduino main Loop function
//=============================================================================
void loop(void)
{
//Start time
unsigned long lTimeWaitEnd;
lTimerStart = millis();
DoBackgroundProcess();
//Read input
CheckVoltage(); // check our voltages...
if (!g_fLowVoltageShutdown) {
// DebugWrite(A0, HIGH);
g_InputController.ControlInput();
// DebugWrite(A0, LOW);
}
WriteOutputs(); // Write Outputs
#ifdef IsRobotUpsideDown
if (!fWalking){// dont do this while walking
g_fRobotUpsideDown = IsRobotUpsideDown; // Grab the current state of the robot...
if (g_fRobotUpsideDown != fRobotUpsideDownPrev) {
// Double check to make sure that it was not a one shot error
g_fRobotUpsideDown = IsRobotUpsideDown; // Grab the current state of the robot...
if (g_fRobotUpsideDown != fRobotUpsideDownPrev) {
fRobotUpsideDownPrev = g_fRobotUpsideDown;
#ifdef DGBSerial
DBGSerial.println(fRobotUpsideDownPrev, DEC);
#endif
}
}
}
// DBGSerial.println(analogRead(0), DEC);
#endif
#ifdef OPT_WALK_UPSIDE_DOWN
if (g_fRobotUpsideDown){
g_InControlState.TravelLength.x = -g_InControlState.TravelLength.x;
g_InControlState.BodyPos.x = -g_InControlState.BodyPos.x;
g_InControlState.SLLeg.x = -g_InControlState.SLLeg.x;
g_InControlState.BodyRot1.z = -g_InControlState.BodyRot1.z;
}
#endif
#ifdef OPT_GPPLAYER
//GP Player
g_ServoDriver.GPPlayer();
if (g_ServoDriver.FIsGPSeqActive())
return; // go back to process the next message
#endif
//Single leg control
SingleLegControl ();
DoBackgroundProcess();
//Gait
GaitSeq();
DoBackgroundProcess();
//Balance calculations
TotalTransX = 0; //reset values used for calculation of balance
TotalTransZ = 0;
TotalTransY = 0;
TotalXBal1 = 0;
TotalYBal1 = 0;
TotalZBal1 = 0;
if (g_InControlState.BalanceMode) {
#ifdef DEBUG
if (g_fDebugOutput) {
TravelRequest = (abs(g_InControlState.TravelLength.x)>cTravelDeadZone) || (abs(g_InControlState.TravelLength.z)>cTravelDeadZone)
|| (abs(g_InControlState.TravelLength.y)>cTravelDeadZone) || (g_InControlState.ForceGaitStepCnt != 0) || fWalking;
DBGSerial.print("T(");
DBGSerial.print(fWalking, DEC);
DBGSerial.print(" ");
DBGSerial.print(g_InControlState.TravelLength.x,DEC);
DBGSerial.print(",");
DBGSerial.print(g_InControlState.TravelLength.y,DEC);
DBGSerial.print(",");
DBGSerial.print(g_InControlState.TravelLength.z,DEC);
DBGSerial.print(")");
}
#endif
for (LegIndex = 0; LegIndex < (CNT_LEGS/2); LegIndex++) { // balance calculations for all Right legs
DoBackgroundProcess();
BalCalcOneLeg (-LegPosX[LegIndex]+GaitPosX[LegIndex], LegPosZ[LegIndex]+GaitPosZ[LegIndex],
(LegPosY[LegIndex]-(short)pgm_read_word(&cInitPosY[LegIndex]))+GaitPosY[LegIndex], LegIndex);
}
for (LegIndex = (CNT_LEGS/2); LegIndex < CNT_LEGS; LegIndex++) { // balance calculations for all Right legs
DoBackgroundProcess();
BalCalcOneLeg(LegPosX[LegIndex]+GaitPosX[LegIndex], LegPosZ[LegIndex]+GaitPosZ[LegIndex],
(LegPosY[LegIndex]-(short)pgm_read_word(&cInitPosY[LegIndex]))+GaitPosY[LegIndex], LegIndex);
}
BalanceBody();
}
//Reset IKsolution indicators
IKSolution = 0 ;
IKSolutionWarning = 0;
IKSolutionError = 0 ;
//Do IK for all Right legs
#ifdef DEBUG
if (g_fDebugOutput && g_InControlState.fRobotOn) {
DBGSerial.print(g_InControlState.GaitStep,DEC);
DBGSerial.print(":");
}
#endif
for (LegIndex = 0; LegIndex < (CNT_LEGS/2); LegIndex++) {
DoBackgroundProcess();
BodyFK(-LegPosX[LegIndex]+g_InControlState.BodyPos.x+GaitPosX[LegIndex] - TotalTransX,
LegPosZ[LegIndex]+g_InControlState.BodyPos.z+GaitPosZ[LegIndex] - TotalTransZ,
LegPosY[LegIndex]+g_InControlState.BodyPos.y+GaitPosY[LegIndex] - TotalTransY,
GaitRotY[LegIndex], LegIndex);
LegIK (LegPosX[LegIndex]-g_InControlState.BodyPos.x+BodyFKPosX-(GaitPosX[LegIndex] - TotalTransX),
LegPosY[LegIndex]+g_InControlState.BodyPos.y-BodyFKPosY+GaitPosY[LegIndex] - TotalTransY,
LegPosZ[LegIndex]+g_InControlState.BodyPos.z-BodyFKPosZ+GaitPosZ[LegIndex] - TotalTransZ, LegIndex);
}
//Do IK for all Left legs
for (LegIndex = (CNT_LEGS/2); LegIndex < CNT_LEGS; LegIndex++) {
DoBackgroundProcess();
BodyFK(LegPosX[LegIndex]-g_InControlState.BodyPos.x+GaitPosX[LegIndex] - TotalTransX,
LegPosZ[LegIndex]+g_InControlState.BodyPos.z+GaitPosZ[LegIndex] - TotalTransZ,
LegPosY[LegIndex]+g_InControlState.BodyPos.y+GaitPosY[LegIndex] - TotalTransY,
GaitRotY[LegIndex], LegIndex);
LegIK (LegPosX[LegIndex]+g_InControlState.BodyPos.x-BodyFKPosX+GaitPosX[LegIndex] - TotalTransX,
LegPosY[LegIndex]+g_InControlState.BodyPos.y-BodyFKPosY+GaitPosY[LegIndex] - TotalTransY,
LegPosZ[LegIndex]+g_InControlState.BodyPos.z-BodyFKPosZ+GaitPosZ[LegIndex] - TotalTransZ, LegIndex);
}
#ifdef OPT_WALK_UPSIDE_DOWN
if (g_fRobotUpsideDown){ //Need to set them back for not messing with the SmoothControl
g_InControlState.BodyPos.x = -g_InControlState.BodyPos.x;
g_InControlState.SLLeg.x = -g_InControlState.SLLeg.x;
g_InControlState.BodyRot1.z = -g_InControlState.BodyRot1.z;
}
#endif
//Check mechanical limits
CheckAngles();
//Write IK errors to leds
LedC = IKSolutionWarning;
LedA = IKSolutionError;
//Drive Servos
if (g_InControlState.fRobotOn) {
if (g_InControlState.fRobotOn && !g_InControlState.fPrev_RobotOn) {
MSound(3, 60, 2000, 80, 2250, 100, 2500);
#ifdef USEXBEE
XBeePlaySounds(3, 60, 2000, 80, 2250, 100, 2500);
#endif
Eyes = 1;
}
//Calculate Servo Move time
if ((abs(g_InControlState.TravelLength.x)>cTravelDeadZone) || (abs(g_InControlState.TravelLength.z)>cTravelDeadZone) ||
(abs(g_InControlState.TravelLength.y*2)>cTravelDeadZone)) {
ServoMoveTime = g_InControlState.gaitCur.NomGaitSpeed + (g_InControlState.InputTimeDelay*2) + g_InControlState.SpeedControl;
//Add aditional delay when Balance mode is on
if (g_InControlState.BalanceMode)
ServoMoveTime = ServoMoveTime + BALANCE_DELAY;
}
else //Movement speed excl. Walking
ServoMoveTime = 200 + g_InControlState.SpeedControl;
// note we broke up the servo driver into start/commit that way we can output all of the servo information
// before we wait and only have the termination information to output after the wait. That way we hopefully