-
Notifications
You must be signed in to change notification settings - Fork 0
/
GPS.ino
1168 lines (1035 loc) · 41.9 KB
/
GPS.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
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
#if GPS
#if defined(TINY_GPS)
#include "tinygps.h"
#endif
#if defined(GPS_SERIAL) || defined(GPS_FROM_OSD) || defined(TINY_GPS)
typedef struct PID_PARAM_ {
float kP;
float kI;
float kD;
float Imax;
} PID_PARAM;
PID_PARAM posholdPID_PARAM;
PID_PARAM poshold_ratePID_PARAM;
PID_PARAM navPID_PARAM;
typedef struct PID_ {
float integrator; // integrator value
int32_t last_input; // last input for derivative
float lastderivative; // last derivative for low-pass filter
float output;
float derivative;
} PID;
PID posholdPID[2];
PID poshold_ratePID[2];
PID navPID[2];
int32_t get_P(int32_t error, struct PID_PARAM_* pid) {
return (float)error * pid->kP;
}
int32_t get_I(int32_t error, float* dt, struct PID_* pid, struct PID_PARAM_* pid_param) {
pid->integrator += ((float)error * pid_param->kI) * *dt;
pid->integrator = constrain(pid->integrator,-pid_param->Imax,pid_param->Imax);
return pid->integrator;
}
int32_t get_D(int32_t input, float* dt, struct PID_* pid, struct PID_PARAM_* pid_param) { // dt in milliseconds
pid->derivative = (input - pid->last_input) / *dt;
/// Low pass filter cut frequency for derivative calculation.
float filter = 7.9577e-3; // Set to "1 / ( 2 * PI * f_cut )";
// Examples for _filter:
// f_cut = 10 Hz -> _filter = 15.9155e-3
// f_cut = 15 Hz -> _filter = 10.6103e-3
// f_cut = 20 Hz -> _filter = 7.9577e-3
// f_cut = 25 Hz -> _filter = 6.3662e-3
// f_cut = 30 Hz -> _filter = 5.3052e-3
// discrete low pass filter, cuts out the
// high frequency noise that can drive the controller crazy
pid->derivative = pid->lastderivative + (*dt / ( filter + *dt)) * (pid->derivative - pid->lastderivative);
// update state
pid->last_input = input;
pid->lastderivative = pid->derivative;
// add in derivative component
return pid_param->kD * pid->derivative;
}
void reset_PID(struct PID_* pid) {
pid->integrator = 0;
pid->last_input = 0;
pid->lastderivative = 0;
}
#define _X 1
#define _Y 0
#define RADX100 0.000174532925
#define CROSSTRACK_GAIN 1
#define NAV_SPEED_MIN 100 // cm/sec
#define NAV_SPEED_MAX 300 // cm/sec
#define NAV_SLOW_NAV true
#define NAV_BANK_MAX 3000 //30deg max banking when navigating (just for security and testing)
static float dTnav; // Delta Time in milliseconds for navigation computations, updated with every good GPS read
static uint16_t GPS_wp_radius = GPS_WP_RADIUS;
static int16_t actual_speed[2] = {0,0};
static float GPS_scaleLonDown; // this is used to offset the shrinking longitude as we go towards the poles
// The difference between the desired rate of travel and the actual rate of travel
// updated after GPS read - 5-10hz
static int16_t rate_error[2];
static int32_t error[2];
//Currently used WP
static int32_t GPS_WP[2];
////////////////////////////////////////////////////////////////////////////////
// Location & Navigation
////////////////////////////////////////////////////////////////////////////////
// This is the angle from the copter to the "next_WP" location in degrees * 100
static int32_t target_bearing;
////////////////////////////////////////////////////////////////////////////////
// Crosstrack
////////////////////////////////////////////////////////////////////////////////
// deg * 100, The original angle to the next_WP when the next_WP was set
// Also used to check when we pass a WP
static int32_t original_target_bearing;
// The amount of angle correction applied to target_bearing to bring the copter back on its optimum path
static int16_t crosstrack_error;
////////////////////////////////////////////////////////////////////////////////
// The location of the copter in relation to home, updated every GPS read (1deg - 100)
// static int32_t home_to_copter_bearing; /* unused */
// distance between plane and home in cm
// static int32_t home_distance; /* unused */
// distance between plane and next_WP in cm
static uint32_t wp_distance;
// used for slow speed wind up when start navigation;
static uint16_t waypoint_speed_gov;
////////////////////////////////////////////////////////////////////////////////////
// moving average filter variables
//
#define GPS_FILTER_VECTOR_LENGTH 5
static uint8_t GPS_filter_index = 0;
static int32_t GPS_filter[2][GPS_FILTER_VECTOR_LENGTH];
static int32_t GPS_filter_sum[2];
static int32_t GPS_read[2];
static int32_t GPS_filtered[2];
static int32_t GPS_degree[2]; //the lat lon degree without any decimals (lat/10 000 000)
static uint16_t fraction3[2];
#endif
// This is the angle from the copter to the "next_WP" location
// with the addition of Crosstrack error in degrees * 100
static int32_t nav_bearing;
// saves the bearing at takeof (1deg = 1) used to rotate to takeoff direction when arrives at home
static int16_t nav_takeoff_bearing;
#if defined(I2C_GPS)
/////////////////////////////////////////////////////////////////////////////////////////
// I2C GPS helper functions
//
// Send a command to the I2C GPS module, first parameter command, second parameter wypoint number
void GPS_I2C_command(uint8_t command, uint8_t wp) {
uint8_t _cmd;
_cmd = (wp << 4) + command;
i2c_rep_start(I2C_GPS_ADDRESS<<1);
i2c_write(I2C_GPS_COMMAND);
i2c_write(_cmd);
}
#endif
#if defined(GPS_SERIAL)
#if defined(INIT_MTK_GPS) || defined(UBLOX)
uint32_t init_speed[5] = {9600,19200,38400,57600,115200};
void SerialGpsPrint(prog_char* str) {
char b;
while(str && (b = pgm_read_byte(str++))) {
SerialWrite(GPS_SERIAL, b);
#if defined(UBLOX)
delay(5);
#endif
}
}
#endif
#if defined(UBLOX)
prog_char UBLOX_INIT[] PROGMEM = { // PROGMEM array must be outside any function !!!
0xB5,0x62,0x06,0x01,0x03,0x00,0xF0,0x05,0x00,0xFF,0x19, //disable all default NMEA messages
0xB5,0x62,0x06,0x01,0x03,0x00,0xF0,0x03,0x00,0xFD,0x15,
0xB5,0x62,0x06,0x01,0x03,0x00,0xF0,0x01,0x00,0xFB,0x11,
0xB5,0x62,0x06,0x01,0x03,0x00,0xF0,0x00,0x00,0xFA,0x0F,
0xB5,0x62,0x06,0x01,0x03,0x00,0xF0,0x02,0x00,0xFC,0x13,
0xB5,0x62,0x06,0x01,0x03,0x00,0xF0,0x04,0x00,0xFE,0x17,
0xB5,0x62,0x06,0x01,0x03,0x00,0x01,0x02,0x01,0x0E,0x47, //set POSLLH MSG rate
0xB5,0x62,0x06,0x01,0x03,0x00,0x01,0x03,0x01,0x0F,0x49, //set STATUS MSG rate
0xB5,0x62,0x06,0x01,0x03,0x00,0x01,0x06,0x01,0x12,0x4F, //set SOL MSG rate
0xB5,0x62,0x06,0x01,0x03,0x00,0x01,0x12,0x01,0x1E,0x67, //set VELNED MSG rate
0xB5,0x62,0x06,0x16,0x08,0x00,0x03,0x07,0x03,0x00,0x51,0x08,0x00,0x00,0x8A,0x41, //set WAAS to EGNOS
0xB5, 0x62, 0x06, 0x08, 0x06, 0x00, 0xC8, 0x00, 0x01, 0x00, 0x01, 0x00, 0xDE, 0x6A //set rate to 5Hz
};
#endif
void GPS_SerialInit() {
SerialOpen(GPS_SERIAL,GPS_BAUD);
delay(1000);
#if defined(UBLOX)
for(uint8_t i=0;i<5;i++){
SerialOpen(GPS_SERIAL,init_speed[i]); // switch UART speed for sending SET BAUDRATE command (NMEA mode)
#if (GPS_BAUD==19200)
SerialGpsPrint(PSTR("$PUBX,41,1,0003,0001,19200,0*23\r\n")); // 19200 baud - minimal speed for 5Hz update rate
#endif
#if (GPS_BAUD==38400)
SerialGpsPrint(PSTR("$PUBX,41,1,0003,0001,38400,0*26\r\n")); // 38400 baud
#endif
#if (GPS_BAUD==57600)
SerialGpsPrint(PSTR("$PUBX,41,1,0003,0001,57600,0*2D\r\n")); // 57600 baud
#endif
#if (GPS_BAUD==115200)
SerialGpsPrint(PSTR("$PUBX,41,1,0003,0001,115200,0*1E\r\n")); // 115200 baud
#endif
while(!SerialTXfree(GPS_SERIAL)) delay(10);
}
delay(200);
SerialOpen(GPS_SERIAL,GPS_BAUD);
for(uint8_t i=0; i<sizeof(UBLOX_INIT); i++) { // send configuration data in UBX protocol
SerialWrite(GPS_SERIAL, pgm_read_byte(UBLOX_INIT+i));
delay(5); //simulating a 38400baud pace (or less), otherwise commands are not accepted by the device.
}
#elif defined(INIT_MTK_GPS) // MTK GPS setup
for(uint8_t i=0;i<5;i++){
SerialOpen(GPS_SERIAL,init_speed[i]); // switch UART speed for sending SET BAUDRATE command
#if (GPS_BAUD==19200)
SerialGpsPrint(PSTR("$PMTK251,19200*22\r\n")); // 19200 baud - minimal speed for 5Hz update rate
#endif
#if (GPS_BAUD==38400)
SerialGpsPrint(PSTR("$PMTK251,38400*27\r\n")); // 38400 baud
#endif
#if (GPS_BAUD==57600)
SerialGpsPrint(PSTR("$PMTK251,57600*2C\r\n")); // 57600 baud
#endif
#if (GPS_BAUD==115200)
SerialGpsPrint(PSTR("$PMTK251,115200*1F\r\n")); // 115200 baud
#endif
while(!SerialTXfree(GPS_SERIAL)) delay(80);
}
// at this point we have GPS working at selected (via #define GPS_BAUD) baudrate
SerialOpen(GPS_SERIAL,GPS_BAUD);
SerialGpsPrint(PSTR("$PMTK314,0,1,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*28\r\n")); // only GGA and RMC sentence
SerialGpsPrint(PSTR("$PMTK220,200*2C\r\n")); // 5 Hz update rate
#endif
}
#endif
void GPS_NewData() {
uint8_t axis;
#if defined(I2C_GPS)
static uint8_t GPS_pids_initialized;
static uint8_t _i2c_gps_status;
//Do not use i2c_writereg, since writing a register does not work if an i2c_stop command is issued at the end
//Still investigating, however with separated i2c_repstart and i2c_write commands works... and did not caused i2c errors on a long term test.
GPS_numSat = (_i2c_gps_status & 0xf0) >> 4;
_i2c_gps_status = i2c_readReg(I2C_GPS_ADDRESS,I2C_GPS_STATUS_00); //Get status register
if (_i2c_gps_status & I2C_GPS_STATUS_3DFIX) { //Check is we have a good 3d fix (numsats>5)
f.GPS_FIX = 1;
#if !defined(DONT_RESET_HOME_AT_ARM)
if (!f.ARMED) {f.GPS_FIX_HOME = 0;} //Clear home position if disarmed
#endif
if (!f.GPS_FIX_HOME && f.ARMED) { //if home is not set set home position to WP#0 and activate it
GPS_reset_home_position();
}
if (_i2c_gps_status & I2C_GPS_STATUS_NEW_DATA) { //Check about new data
if (GPS_update) { GPS_update = 0;} else { GPS_update = 1;} //Fancy flash on GUI :D
if (!GPS_pids_initialized) {
GPS_set_pids();
GPS_pids_initialized = 1;
}
//Read GPS data for distance, heading and gps position
i2c_rep_start(I2C_GPS_ADDRESS<<1);
i2c_write(I2C_GPS_NAV_BEARING); //Start read from here 2x2 bytes distance and direction
i2c_rep_start((I2C_GPS_ADDRESS<<1)|1);
uint8_t *varptr = (uint8_t *)&nav_bearing;
*varptr++ = i2c_readAck();
*varptr = i2c_readAck();
varptr = (uint8_t *)&GPS_directionToHome;
*varptr++ = i2c_readAck();
*varptr = i2c_readAck();
GPS_directionToHome = GPS_directionToHome / 100; // 1deg =1000 in the reg, downsize
if (GPS_directionToHome>180) GPS_directionToHome -= 360;
varptr = (uint8_t *)&GPS_distanceToHome;
*varptr++ = i2c_readAck();
*varptr = i2c_readNak();
GPS_distanceToHome = GPS_distanceToHome / 100; //register is in CM, we need in meter
i2c_rep_start(I2C_GPS_ADDRESS<<1);
i2c_write(I2C_GPS_LOCATION); //Start read from here 2x2 bytes distance and direction
i2c_rep_start((I2C_GPS_ADDRESS<<1)|1);
varptr = (uint8_t *)&GPS_coord[LAT]; // for latitude displaying
*varptr++ = i2c_readAck();
*varptr++ = i2c_readAck();
*varptr++ = i2c_readAck();
*varptr = i2c_readAck();
varptr = (uint8_t *)&GPS_coord[LON]; // for longitude displaying
*varptr++ = i2c_readAck();
*varptr++ = i2c_readAck();
*varptr++ = i2c_readAck();
*varptr = i2c_readAck();
varptr = (uint8_t *)&nav[LAT];
*varptr++ = i2c_readAck();
*varptr++ = i2c_readAck();
varptr = (uint8_t *)&nav[LON];
*varptr++ = i2c_readAck();
*varptr++ = i2c_readNak();
i2c_rep_start(I2C_GPS_ADDRESS<<1);
i2c_write(I2C_GPS_GROUND_SPEED);
i2c_rep_start((I2C_GPS_ADDRESS<<1)|1);
varptr = (uint8_t *)&GPS_speed; // speed in cm/s for OSD
*varptr++ = i2c_readAck();
*varptr = i2c_readAck();
varptr = (uint8_t *)&GPS_altitude; // altitude in meters for OSD
*varptr++ = i2c_readAck();
*varptr = i2c_readAck();
//GPS_ground_course
varptr = (uint8_t *)&GPS_ground_course;
*varptr++ = i2c_readAck();
*varptr = i2c_readNak();
if (!f.GPS_FIX_HOME) { //If we don't have home set, do not display anything
GPS_distanceToHome = 0;
GPS_directionToHome = 0;
}
//Adjust heading when navigating
if (f.GPS_HOME_MODE)
{ if ( !(_i2c_gps_status & I2C_GPS_STATUS_WP_REACHED) )
{
//Tail control
if (NAV_CONTROLS_HEADING) {
if (NAV_TAIL_FIRST) {
magHold = nav_bearing/100-180;
if (magHold > 180) magHold -= 360;
if (magHold < -180) magHold += 360;
} else {
magHold = nav_bearing/100;
}
}
} else { //Home position reached
if (NAV_SET_TAKEOFF_HEADING) { magHold = nav_takeoff_bearing; }
}
}
}
} else { //We don't have a fix zero out distance and bearing (for safety reasons)
GPS_distanceToHome = 0;
GPS_directionToHome = 0;
GPS_numSat = 0;
}
#endif
#if defined(GPS_SERIAL) || defined(TINY_GPS) || defined(GPS_FROM_OSD)
#if defined(GPS_SERIAL)
uint8_t c = SerialAvailable(GPS_SERIAL);
while (c--) {
//while (SerialAvailable(GPS_SERIAL)) {
if (GPS_newFrame(SerialRead(GPS_SERIAL))) {
#elif defined(TINY_GPS)
{
{
tinygps_query();
#elif defined(GPS_FROM_OSD)
{
if(GPS_update & 2) { // Once second bit of GPS_update is set, indicate new GPS datas is readed from OSD - all in right format.
GPS_update &= 1; // We have: GPS_fix(0-2), GPS_numSat(0-15), GPS_coord[LAT & LON](signed, in 1/10 000 000 degres), GPS_altitude(signed, in meters) and GPS_speed(in cm/s)
#endif
if (GPS_update == 1) GPS_update = 0; else GPS_update = 1;
if (f.GPS_FIX && GPS_numSat >= 5) {
#if !defined(DONT_RESET_HOME_AT_ARM)
if (!f.ARMED) {f.GPS_FIX_HOME = 0;}
#endif
if (!f.GPS_FIX_HOME && f.ARMED) {
GPS_reset_home_position();
}
//Apply moving average filter to GPS data
#if defined(GPS_FILTERING)
GPS_filter_index = (GPS_filter_index+1) % GPS_FILTER_VECTOR_LENGTH;
for (axis = 0; axis< 2; axis++) {
GPS_read[axis] = GPS_coord[axis]; //latest unfiltered data is in GPS_latitude and GPS_longitude
GPS_degree[axis] = GPS_read[axis] / 10000000; // get the degree to assure the sum fits to the int32_t
// How close we are to a degree line ? its the first three digits from the fractions of degree
// later we use it to Check if we are close to a degree line, if yes, disable averaging,
fraction3[axis] = (GPS_read[axis]- GPS_degree[axis]*10000000) / 10000;
GPS_filter_sum[axis] -= GPS_filter[axis][GPS_filter_index];
GPS_filter[axis][GPS_filter_index] = GPS_read[axis] - (GPS_degree[axis]*10000000);
GPS_filter_sum[axis] += GPS_filter[axis][GPS_filter_index];
GPS_filtered[axis] = GPS_filter_sum[axis] / GPS_FILTER_VECTOR_LENGTH + (GPS_degree[axis]*10000000);
if ( nav_mode == NAV_MODE_POSHOLD) { //we use gps averaging only in poshold mode...
if ( fraction3[axis]>1 && fraction3[axis]<999 ) GPS_coord[axis] = GPS_filtered[axis];
}
}
#endif
//dTnav calculation
//Time for calculating x,y speed and navigation pids
static uint32_t nav_loopTimer;
dTnav = (float)(millis() - nav_loopTimer)/ 1000.0;
nav_loopTimer = millis();
// prevent runup from bad GPS
dTnav = min(dTnav, 1.0);
//calculate distance and bearings for gui and other stuff continously - From home to copter
uint32_t dist;
int32_t dir;
GPS_distance_cm_bearing(&GPS_coord[LAT],&GPS_coord[LON],&GPS_home[LAT],&GPS_home[LON],&dist,&dir);
GPS_distanceToHome = dist/100;
GPS_directionToHome = dir/100;
if (!f.GPS_FIX_HOME) { //If we don't have home set, do not display anything
GPS_distanceToHome = 0;
GPS_directionToHome = 0;
}
//calculate the current velocity based on gps coordinates continously to get a valid speed at the moment when we start navigating
GPS_calc_velocity();
if (f.GPS_HOLD_MODE || f.GPS_HOME_MODE){ //ok we are navigating
//do gps nav calculations here, these are common for nav and poshold
GPS_distance_cm_bearing(&GPS_coord[LAT],&GPS_coord[LON],&GPS_WP[LAT],&GPS_WP[LON],&wp_distance,&target_bearing);
GPS_calc_location_error(&GPS_WP[LAT],&GPS_WP[LON],&GPS_coord[LAT],&GPS_coord[LON]);
switch (nav_mode) {
case NAV_MODE_POSHOLD:
//Desired output is in nav_lat and nav_lon where 1deg inclination is 100
GPS_calc_poshold();
break;
case NAV_MODE_WP:
int16_t speed = GPS_calc_desired_speed(NAV_SPEED_MAX, NAV_SLOW_NAV); //slow navigation
// use error as the desired rate towards the target
//Desired output is in nav_lat and nav_lon where 1deg inclination is 100
GPS_calc_nav_rate(speed);
//Tail control
if (NAV_CONTROLS_HEADING) {
if (NAV_TAIL_FIRST) {
magHold = wrap_18000(nav_bearing-18000)/100;
} else {
magHold = nav_bearing/100;
}
}
// Are we there yet ?(within 2 meters of the destination)
if ((wp_distance <= GPS_wp_radius) || check_missed_wp()){ //if yes switch to poshold mode
nav_mode = NAV_MODE_POSHOLD;
if (NAV_SET_TAKEOFF_HEADING) { magHold = nav_takeoff_bearing; }
}
break;
}
} //end of gps calcs
}
}
}
#endif
}
void GPS_reset_home_position() {
if (f.GPS_FIX && GPS_numSat >= 5) {
#if defined(I2C_GPS)
//set current position as home
GPS_I2C_command(I2C_GPS_COMMAND_SET_WP,0); //WP0 is the home position
#else
GPS_home[LAT] = GPS_coord[LAT];
GPS_home[LON] = GPS_coord[LON];
GPS_calc_longitude_scaling(GPS_coord[LAT]); //need an initial value for distance and bearing calc
#endif
nav_takeoff_bearing = heading; //save takeoff heading
//Set ground altitude
f.GPS_FIX_HOME = 1;
}
}
//reset navigation (stop the navigation processor, and clear nav)
void GPS_reset_nav() {
uint8_t i;
for(i=0;i<2;i++) {
GPS_angle[i] = 0;
nav_rated[i] = 0;
nav[i] = 0;
#if defined(I2C_GPS)
//GPS_I2C_command(I2C_GPS_COMMAND_STOP_NAV,0);
#else
reset_PID(&posholdPID[i]);
reset_PID(&poshold_ratePID[i]);
reset_PID(&navPID[i]);
#endif
}
}
//Get the relevant P I D values and set the PID controllers
void GPS_set_pids() {
#if defined(GPS_SERIAL) || defined(GPS_FROM_OSD) || defined(TINY_GPS)
posholdPID_PARAM.kP = (float)conf.P8[PIDPOS]/100.0;
posholdPID_PARAM.kI = (float)conf.I8[PIDPOS]/100.0;
posholdPID_PARAM.Imax = POSHOLD_RATE_IMAX * 100;
poshold_ratePID_PARAM.kP = (float)conf.P8[PIDPOSR]/10.0;
poshold_ratePID_PARAM.kI = (float)conf.I8[PIDPOSR]/100.0;
poshold_ratePID_PARAM.kD = (float)conf.D8[PIDPOSR]/1000.0;
poshold_ratePID_PARAM.Imax = POSHOLD_RATE_IMAX * 100;
navPID_PARAM.kP = (float)conf.P8[PIDNAVR]/10.0;
navPID_PARAM.kI = (float)conf.I8[PIDNAVR]/100.0;
navPID_PARAM.kD = (float)conf.D8[PIDNAVR]/1000.0;
navPID_PARAM.Imax = POSHOLD_RATE_IMAX * 100;
#endif
#if defined(I2C_GPS)
i2c_rep_start(I2C_GPS_ADDRESS<<1);
i2c_write(I2C_GPS_HOLD_P);
i2c_write(conf.P8[PIDPOS]);
i2c_write(conf.I8[PIDPOS]);
i2c_rep_start(I2C_GPS_ADDRESS<<1);
i2c_write(I2C_GPS_HOLD_RATE_P);
i2c_write(conf.P8[PIDPOSR]);
i2c_write(conf.I8[PIDPOSR]);
i2c_write(conf.D8[PIDPOSR]);
i2c_rep_start(I2C_GPS_ADDRESS<<1);
i2c_write(I2C_GPS_NAV_P);
i2c_write(conf.P8[PIDNAVR]);
i2c_write(conf.I8[PIDNAVR]);
i2c_write(conf.D8[PIDNAVR]);
GPS_I2C_command(I2C_GPS_COMMAND_UPDATE_PIDS,0);
uint8_t nav_flags = 0;
#if defined(GPS_FILTERING)
nav_flags += I2C_NAV_FLAG_GPS_FILTER;
#endif
#if defined(GPS_LOW_SPEED_D_FILTER)
nav_flags += I2C_NAV_FLAG_LOW_SPEED_D_FILTER;
#endif
i2c_rep_start(I2C_GPS_ADDRESS<<1);
i2c_write(I2C_GPS_NAV_FLAGS);
i2c_write(nav_flags);
i2c_rep_start(I2C_GPS_ADDRESS<<1);
i2c_write(I2C_GPS_WP_RADIUS);
i2c_write(GPS_WP_RADIUS & 0x00FF); // lower eight bit
i2c_write(GPS_WP_RADIUS >> 8); // upper eight bit
#endif
}
#if defined (TINY_GPS)
int32_t GPS_coord_to_decimal(struct coord *c) {
#define GPS_SCALE_FACTOR 10000000L
uint32_t deg = 0;
uint8_t i;
deg = (uint32_t)c->deg * GPS_SCALE_FACTOR;
uint32_t min = 0;
min = (uint32_t)c->min * GPS_SCALE_FACTOR;
/* add up the BCD fractions */
uint16_t divisor = (uint16_t)GPS_SCALE_FACTOR/10;
for (i=0; i<NMEA_MINUTE_FRACTS; i++) {
uint8_t b = c->frac[i/2];
uint8_t n = (i%2 ? b&0x0F : b>>4);
min += n*(divisor);
divisor /= 10;
}
/* now sum up degrees and minutes */
return deg + min/60;
}
#endif
//It was mobed here since even i2cgps code needs it
int32_t wrap_18000(int32_t ang) {
if (ang > 18000) ang -= 36000;
if (ang < -18000) ang += 36000;
return ang;
}
//OK here is the onboard GPS code
#if defined(GPS_SERIAL) || defined(GPS_FROM_OSD) || defined(TINY_GPS)
////////////////////////////////////////////////////////////////////////////////////
//PID based GPS navigation functions
//Author : EOSBandi
//Based on code and ideas from the Arducopter team: Jason Short,Randy Mackay, Pat Hickey, Jose Julio, Jani Hirvinen
//Andrew Tridgell, Justin Beech, Adam Rivera, Jean-Louis Naudin, Roberto Navoni
////////////////////////////////////////////////////////////////////////////////////
// this is used to offset the shrinking longitude as we go towards the poles
// It's ok to calculate this once per waypoint setting, since it changes a little within the reach of a multicopter
//
void GPS_calc_longitude_scaling(int32_t lat) {
float rads = (abs((float)lat) / 10000000.0) * 0.0174532925;
GPS_scaleLonDown = cos(rads);
}
////////////////////////////////////////////////////////////////////////////////////
// Sets the waypoint to navigate, reset neccessary variables and calculate initial values
//
void GPS_set_next_wp(int32_t* lat, int32_t* lon) {
GPS_WP[LAT] = *lat;
GPS_WP[LON] = *lon;
GPS_calc_longitude_scaling(*lat);
GPS_distance_cm_bearing(&GPS_coord[LAT],&GPS_coord[LON],&GPS_WP[LAT],&GPS_WP[LON],&wp_distance,&target_bearing);
nav_bearing = target_bearing;
GPS_calc_location_error(&GPS_WP[LAT],&GPS_WP[LON],&GPS_coord[LAT],&GPS_coord[LON]);
original_target_bearing = target_bearing;
waypoint_speed_gov = NAV_SPEED_MIN;
}
////////////////////////////////////////////////////////////////////////////////////
// Check if we missed the destination somehow
//
static bool check_missed_wp() {
int32_t temp;
temp = target_bearing - original_target_bearing;
temp = wrap_18000(temp);
return (abs(temp) > 10000); // we passed the waypoint by 100 degrees
}
////////////////////////////////////////////////////////////////////////////////////
// Get distance between two points in cm
// Get bearing from pos1 to pos2, returns an 1deg = 100 precision
void GPS_distance_cm_bearing(int32_t* lat1, int32_t* lon1, int32_t* lat2, int32_t* lon2,uint32_t* dist, int32_t* bearing) {
float dLat = *lat2 - *lat1; // difference of latitude in 1/10 000 000 degrees
float dLon = (float)(*lon2 - *lon1) * GPS_scaleLonDown;
*dist = sqrt(sq(dLat) + sq(dLon)) * 1.113195;
*bearing = 9000.0f + atan2(-dLat, dLon) * 5729.57795f; //Convert the output redians to 100xdeg
if (*bearing < 0) *bearing += 36000;
}
////////////////////////////////////////////////////////////////////////////////////
// keep old calculation function for compatibility (could be removed later) distance in meters, bearing in degree
//
void GPS_distance(int32_t lat1, int32_t lon1, int32_t lat2, int32_t lon2, uint16_t* dist, int16_t* bearing) {
uint32_t d1;
int32_t d2;
GPS_distance_cm_bearing(&lat1,&lon1,&lat2,&lon2,&d1,&d2);
*dist = d1 / 100; //convert to meters
*bearing = d2 / 100; //convert to degrees
}
////////////////////////////////////////////////////////////////////////////////////
// Calculate our current speed vector from gps position data
//
static void GPS_calc_velocity(){
static int16_t speed_old[2] = {0,0};
static int32_t last[2] = {0,0};
static uint8_t init = 0;
// y_GPS_speed positve = Up
// x_GPS_speed positve = Right
if (init) {
float tmp = 1.0/dTnav;
actual_speed[_X] = (float)(GPS_coord[LON] - last[LON]) * GPS_scaleLonDown * tmp;
actual_speed[_Y] = (float)(GPS_coord[LAT] - last[LAT]) * tmp;
actual_speed[_X] = (actual_speed[_X] + speed_old[_X]) / 2;
actual_speed[_Y] = (actual_speed[_Y] + speed_old[_Y]) / 2;
speed_old[_X] = actual_speed[_X];
speed_old[_Y] = actual_speed[_Y];
}
init=1;
last[LON] = GPS_coord[LON];
last[LAT] = GPS_coord[LAT];
}
////////////////////////////////////////////////////////////////////////////////////
// Calculate a location error between two gps coordinates
// Because we are using lat and lon to do our distance errors here's a quick chart:
// 100 = 1m
// 1000 = 11m = 36 feet
// 1800 = 19.80m = 60 feet
// 3000 = 33m
// 10000 = 111m
//
static void GPS_calc_location_error( int32_t* target_lat, int32_t* target_lng, int32_t* gps_lat, int32_t* gps_lng ) {
error[LON] = (float)(*target_lng - *gps_lng) * GPS_scaleLonDown; // X Error
error[LAT] = *target_lat - *gps_lat; // Y Error
}
////////////////////////////////////////////////////////////////////////////////////
// Calculate nav_lat and nav_lon from the x and y error and the speed
//
static void GPS_calc_poshold() {
int32_t d;
int32_t target_speed;
uint8_t axis;
for (axis=0;axis<2;axis++) {
target_speed = get_P(error[axis], &posholdPID_PARAM); // calculate desired speed from lat/lon error
target_speed = constrain(target_speed,-100,100);
rate_error[axis] = target_speed - actual_speed[axis]; // calc the speed error
nav[axis] =
get_P(rate_error[axis], &poshold_ratePID_PARAM)
+get_I(rate_error[axis] + error[axis], &dTnav, &poshold_ratePID[axis], &poshold_ratePID_PARAM);
d = get_D(error[axis], &dTnav, &poshold_ratePID[axis], &poshold_ratePID_PARAM);
d = constrain(d, -2000, 2000);
// get rid of noise
#if defined(GPS_LOW_SPEED_D_FILTER)
if(abs(actual_speed[axis]) < 50) d = 0;
#endif
nav[axis] +=d;
nav[axis] = constrain(nav[axis], -NAV_BANK_MAX, NAV_BANK_MAX);
navPID[axis].integrator = poshold_ratePID[axis].integrator;
}
}
////////////////////////////////////////////////////////////////////////////////////
// Calculate the desired nav_lat and nav_lon for distance flying such as RTH
//
static void GPS_calc_nav_rate(uint16_t max_speed) {
float trig[2];
uint8_t axis;
// push us towards the original track
GPS_update_crosstrack();
// nav_bearing includes crosstrack
float temp = (9000l - nav_bearing) * RADX100;
trig[_X] = cos(temp);
trig[_Y] = sin(temp);
for (axis=0;axis<2;axis++) {
rate_error[axis] = (trig[axis] * max_speed) - actual_speed[axis];
rate_error[axis] = constrain(rate_error[axis], -1000, 1000);
// P + I + D
nav[axis] =
get_P(rate_error[axis], &navPID_PARAM)
+get_I(rate_error[axis], &dTnav, &navPID[axis], &navPID_PARAM)
+get_D(rate_error[axis], &dTnav, &navPID[axis], &navPID_PARAM);
nav[axis] = constrain(nav[axis], -NAV_BANK_MAX, NAV_BANK_MAX);
poshold_ratePID[axis].integrator = navPID[axis].integrator;
}
}
////////////////////////////////////////////////////////////////////////////////////
// Calculating cross track error, this tries to keep the copter on a direct line
// when flying to a waypoint.
//
static void GPS_update_crosstrack(void) {
if (abs(wrap_18000(target_bearing - original_target_bearing)) < 4500) { // If we are too far off or too close we don't do track following
float temp = (target_bearing - original_target_bearing) * RADX100;
crosstrack_error = sin(temp) * (wp_distance * CROSSTRACK_GAIN); // Meters we are off track line
nav_bearing = target_bearing + constrain(crosstrack_error, -3000, 3000);
nav_bearing = wrap_36000(nav_bearing);
}else{
nav_bearing = target_bearing;
}
}
////////////////////////////////////////////////////////////////////////////////////
// Determine desired speed when navigating towards a waypoint, also implement slow
// speed rampup when starting a navigation
//
// |< WP Radius
// 0 1 2 3 4 5 6 7 8m
// ...|...|...|...|...|...|...|...|
// 100 | 200 300 400cm/s
// | +|+
// |< we should slow to 1.5 m/s as we hit the target
//
static uint16_t GPS_calc_desired_speed(uint16_t max_speed, bool _slow) {
// max_speed is default 400 or 4m/s
if(_slow){
max_speed = min(max_speed, wp_distance / 2);
//max_speed = max(max_speed, 0);
}else{
max_speed = min(max_speed, wp_distance);
max_speed = max(max_speed, NAV_SPEED_MIN); // go at least 100cm/s
}
// limit the ramp up of the speed
// waypoint_speed_gov is reset to 0 at each new WP command
if(max_speed > waypoint_speed_gov){
waypoint_speed_gov += (int)(100.0 * dTnav); // increase at .5/ms
max_speed = waypoint_speed_gov;
}
return max_speed;
}
////////////////////////////////////////////////////////////////////////////////////
// Utilities
//
int32_t wrap_36000(int32_t ang) {
if (ang > 36000) ang -= 36000;
if (ang < 0) ang += 36000;
return ang;
}
// This code is used for parsing NMEA data
#if defined(GPS_SERIAL)
/* Alex optimization
The latitude or longitude is coded this way in NMEA frames
dm.f coded as degrees + minutes + minute decimal
Where:
- d can be 1 or more char long. generally: 2 char long for latitude, 3 char long for longitude
- m is always 2 char long
- f can be 1 or more char long
This function converts this format in a unique unsigned long where 1 degree = 10 000 000
EOS increased the precision here, even if we think that the gps is not precise enough, with 10e5 precision it has 76cm resolution
with 10e7 it's around 1 cm now. Increasing it further is irrelevant, since even 1cm resolution is unrealistic, however increased
resolution also increased precision of nav calculations
*/
/* This calc adds approc 2km error to the gps coordinates reverted back to the original working one
uint32_t GPS_coord_to_degrees(char* s) {
char *p = s, *d = s;
uint8_t min, deg = 0;
uint16_t frac = 0, mult = 10000;
while(*p) { // parse the string until its end
if (d != s) {frac+=(*p-'0')*mult;mult/=10;} // calculate only fractional part on up to 5 digits (d != s condition is true when the . is located)
if (*p == '.') d=p; // locate '.' char in the string
p++;
}
if (p==s) return 0;
while (s<d-2) {deg *= 10;deg += *(s++)-'0';} // convert degrees : all chars before minutes ; for the first iteration, deg = 0
min = *(d-1)-'0' + (*(d-2)-'0')*10; // convert minutes : 2 previous char before '.'
return deg * 10000000UL + (min * 100000UL + frac)*10UL / 6;
}
*/
#define DIGIT_TO_VAL(_x) (_x - '0')
uint32_t GPS_coord_to_degrees(char* s) {
char *p, *q;
uint8_t deg = 0, min = 0;
unsigned int frac_min = 0;
uint8_t i;
// scan for decimal point or end of field
for (p = s; isdigit(*p); p++) ;
q = s;
// convert degrees
while ((p - q) > 2) {
if (deg)
deg *= 10;
deg += DIGIT_TO_VAL(*q++);
}
// convert minutes
while (p > q) {
if (min)
min *= 10;
min += DIGIT_TO_VAL(*q++);
}
// convert fractional minutes
// expect up to four digits, result is in
// ten-thousandths of a minute
if (*p == '.') {
q = p + 1;
for (i = 0; i < 4; i++) {
frac_min *= 10;
if (isdigit(*q))
frac_min += *q++ - '0';
}
}
return deg * 10000000UL + (min * 1000000UL + frac_min*100UL) / 6;
}
// helper functions
uint16_t grab_fields(char* src, uint8_t mult) { // convert string to uint16
uint8_t i;
uint16_t tmp = 0;
for(i=0; src[i]!=0; i++) {
if(src[i] == '.') {
i++;
if(mult==0) break;
else src[i+mult] = 0;
}
tmp *= 10;
if(src[i] >='0' && src[i] <='9') tmp += src[i]-'0';
}
return tmp;
}
uint8_t hex_c(uint8_t n) { // convert '0'..'9','A'..'F' to 0..15
n -= '0';
if(n>9) n -= 7;
n &= 0x0F;
return n;
}
bool GPS_newFrame(char c) {
#if defined(NMEA)
return GPS_NMEA_newFrame(c);
#endif
#if defined(UBLOX)
return GPS_UBLOX_newFrame(c);
#endif
}
#if defined(NMEA)
/* This is a light implementation of a GPS frame decoding
This should work with most of modern GPS devices configured to output NMEA frames.
It assumes there are some NMEA GGA frames to decode on the serial bus
Here we use only the following data :
- latitude
- longitude
- GPS fix is/is not ok
- GPS num sat (4 is enough to be +/- reliable)
- GPS altitude
- GPS speed
*/
#define FRAME_GGA 1
#define FRAME_RMC 2
bool GPS_NMEA_newFrame(char c) {
uint8_t frameOK = 0;
static uint8_t param = 0, offset = 0, parity = 0;
static char string[15];
static uint8_t checksum_param, frame = 0;
if (c == '$') {
param = 0; offset = 0; parity = 0;
} else if (c == ',' || c == '*') {
string[offset] = 0;
if (param == 0) { //frame identification
frame = 0;
if (string[0] == 'G' && string[1] == 'P' && string[2] == 'G' && string[3] == 'G' && string[4] == 'A') frame = FRAME_GGA;
if (string[0] == 'G' && string[1] == 'P' && string[2] == 'R' && string[3] == 'M' && string[4] == 'C') frame = FRAME_RMC;
} else if (frame == FRAME_GGA) {
if (param == 2) {GPS_coord[LAT] = GPS_coord_to_degrees(string);}
else if (param == 3 && string[0] == 'S') GPS_coord[LAT] = -GPS_coord[LAT];
else if (param == 4) {GPS_coord[LON] = GPS_coord_to_degrees(string);}
else if (param == 5 && string[0] == 'W') GPS_coord[LON] = -GPS_coord[LON];
else if (param == 6) {f.GPS_FIX = (string[0] > '0');}
else if (param == 7) {GPS_numSat = grab_fields(string,0);}
else if (param == 9) {GPS_altitude = grab_fields(string,0);} // altitude in meters added by Mis
} else if (frame == FRAME_RMC) {
if (param == 7) {GPS_speed = ((uint32_t)grab_fields(string,1)*5144L)/1000L;} //gps speed in cm/s will be used for navigation
else if (param == 8) {GPS_ground_course = grab_fields(string,1); } //ground course deg*10
}
param++; offset = 0;
if (c == '*') checksum_param=1;
else parity ^= c;
} else if (c == '\r' || c == '\n') {
if (checksum_param) { //parity checksum
uint8_t checksum = hex_c(string[0]);
checksum <<= 4;
checksum += hex_c(string[1]);
if (checksum == parity) frameOK = 1;
}
checksum_param=0;
} else {
if (offset < 15) string[offset++] = c;
if (!checksum_param) parity ^= c;
}
if (frame) GPS_Present = 1;
return frameOK && (frame==FRAME_GGA);
}
#endif //NMEA
#if defined(UBLOX)
struct ubx_header {
uint8_t preamble1;
uint8_t preamble2;
uint8_t msg_class;
uint8_t msg_id;
uint16_t length;
};
struct ubx_nav_posllh {
uint32_t time; // GPS msToW
int32_t longitude;
int32_t latitude;
int32_t altitude_ellipsoid;
int32_t altitude_msl;
uint32_t horizontal_accuracy;
uint32_t vertical_accuracy;
};
struct ubx_nav_solution {
uint32_t time;
int32_t time_nsec;
int16_t week;
uint8_t fix_type;
uint8_t fix_status;
int32_t ecef_x;
int32_t ecef_y;
int32_t ecef_z;
uint32_t position_accuracy_3d;
int32_t ecef_x_velocity;
int32_t ecef_y_velocity;
int32_t ecef_z_velocity;
uint32_t speed_accuracy;
uint16_t position_DOP;
uint8_t res;
uint8_t satellites;