-
Notifications
You must be signed in to change notification settings - Fork 0
/
I2C_GPS_NAV.ino
1544 lines (1319 loc) · 54.6 KB
/
I2C_GPS_NAV.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
/*******************************************************************************************************************************
* I2CGPS - Inteligent GPS and NAV module for MultiWii by EOSBandi
* V2.1
*
* This program implements position hold and navigational functions for MultiWii by offloading caclulations and gps parsing
* into a secondary arduino processor connected to the MultiWii via i2c.
* Once activated it outputs desired banking in a lat/lon coordinate system, which can be easily rotated into the copter's frame of reference.
*
* Navigation and Position hold routines and PI/PID libraries are 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
* Status blink code from Guru_florida
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* any later version. see <http://www.gnu.org/licenses/>
* This library is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
* General Public License for more details.
***********************************************************************************************************************************/
#define VERSION 21 //Software version for cross checking
#include "WireMW.h"
#include "PIDCtrl.h"
#include "PICtrl.h"
#include "LeadFilter.h"
#include "registers.h" //Register definitions
#include "config.h"
#define REG_MAP_SIZE sizeof(i2c_dataset) //size of register map
#define MAX_SENT_BYTES 0x0C //maximum amount of data that I could receive from a master device (register, plus 11 byte waypoint data)
#define LAT 0
#define LON 1
///////////////////////////////////////////////////////////////////////////////////////////////////
// Which command I got from the host ? in GPSMode variable
#define GPSMODE_NONAV 0 // no navigation
#define GPSMODE_HOLD 1 // pos hold
#define GPSMODE_WP 2 // wp navigation
///////////////////////////////////////////////////////////////////////////////////////////////////
// Navigation state machine states (nav_mode)
#define NAV_MODE_NONE 0
#define NAV_MODE_POSHOLD 1
#define NAV_MODE_WP 2
// Convert deg*100 to radians
#define RADX100 0.000174532925
//Blink feedback, by guru_florida
#define BLINK_INTERVAL 90
typedef struct {
uint8_t new_data:1;
uint8_t gps2dfix:1;
uint8_t gps3dfix:1;
uint8_t wp_reached:1;
uint8_t numsats:4;
} STATUS_REGISTER;
typedef struct {
uint8_t command:4;
uint8_t wp:4;
} COMMAND_REGISTER;
typedef struct {
uint8_t active_wp:4;
uint8_t pervious_wp:4;
} WAYPOINT_REGISTER;
typedef struct {
long lat; //degree*10 000 000
long lon; //degree*10 000 000
} GPS_COORDINATES;
typedef struct {
GPS_COORDINATES position; //GPS coordinate of the waypoint
uint16_t altitude; //altitude of the waypoint in meters (altitude is relative to the startup altitude)
uint8_t flags; //to be defined
} WAYPOINT;
typedef struct {
//Status and command registers
STATUS_REGISTER status; // 0x00 status register
COMMAND_REGISTER command; // 0x01 command register
WAYPOINT_REGISTER wp_register; // 0x02 waypoint register (current, previus)
uint8_t sw_version; // 0x03 Version of the I2C_GPS sw
uint8_t res3; // 0x04 reserved for future use
uint8_t res4; // 0x05 reserved for future use
uint8_t res5; // 0x06 reserved for future use
//GPS & navigation data
GPS_COORDINATES gps_loc; // current location (8 byte) lat,lon
int16_t nav_lat; // The desired bank towards North (Positive) or South (Negative) 1 deg = 100 max 30deg (3000)
int16_t nav_lon; // The desired bank towards East (Positive) or West (Negative) 1 deg = 100 max 30deg (3000)
uint32_t wp_distance; // distance to active coordinates (calculated) in cm
int16_t wp_target_bearing; // direction to active coordinates (calculated) 1deg = 10 / -1800 - 1800
int16_t nav_bearing; // crosstrack corrected navigational bearing 1deg = 10
int16_t home_to_copter_bearing; // 1deg = 10
uint16_t distance_to_home; // distance to home in cm
uint16_t ground_speed; // ground speed from gps m/s*100
int16_t altitude; // gps altitude
uint16_t ground_course; // GPS ground course
uint16_t res6; // reserved for future use
uint32_t time; // UTC Time from GPS
//Parameters
uint8_t nav_crosstrack_gain; // Crosstrack gain *100 (1 - 0.01 , 100 - 1)
uint8_t nav_speed_min; // minimum speed for navigation cm/s
uint16_t nav_speed_max; // maxiumum speed for navigation cm/s
uint16_t nav_bank_max; // maximum banking 1deg = 100, 30deg = 3000
uint16_t wp_radius; // waypoint radius, if we within this radius, then we considered that the wp is reached in cm
uint8_t nav_flags; // navigational flags to be defined
//PID values
uint8_t poshold_p; // *100
uint8_t poshold_i; // *100
uint8_t poshold_imax; // *1
uint8_t poshold_rate_p; // *10
uint8_t poshold_rate_i; // *100
uint8_t poshold_rate_d; // *1000
uint8_t poshold_rate_imax; // *1
uint8_t nav_p; // *10
uint8_t nav_i; // *100
uint8_t nav_d; // *1000
uint8_t nav_imax; // *1
WAYPOINT gps_wp[16]; // 16 waypoints, WP#0 is RTH position
#if defined(HCSR04)
int16_t Sonar_distance; //sonar reading
#endif
} I2C_REGISTERS;
static I2C_REGISTERS i2c_dataset;
static GPS_COORDINATES _target; //internal target location register
static uint8_t receivedCommands[MAX_SENT_BYTES];
static uint8_t new_command; //new command received (!=0)
//////////////////////////////////////////////////////////////////////////////
// Variables and controllers
//PID controllers
PICtrl pi_poshold_lat(POSHOLD_P, POSHOLD_I, POSHOLD_IMAX * 100);
PICtrl pi_poshold_lon(POSHOLD_P, POSHOLD_I, POSHOLD_IMAX * 100);
PIDCtrl pid_poshold_rate_lat(POSHOLD_RATE_P, POSHOLD_RATE_I, POSHOLD_RATE_D, POSHOLD_RATE_IMAX * 100);
PIDCtrl pid_poshold_rate_lon(POSHOLD_RATE_P, POSHOLD_RATE_I, POSHOLD_RATE_D, POSHOLD_RATE_IMAX * 100);
PIDCtrl pid_nav_lat(NAV_P,NAV_I,NAV_D,NAV_IMAX * 100);
PIDCtrl pid_nav_lon(NAV_P,NAV_I,NAV_D,NAV_IMAX * 100);
LeadFilter xLeadFilter; // Long GPS lag filter
LeadFilter yLeadFilter; // Lat GPS lag filter
// used to track the elapsed time between GPS reads
static uint32_t nav_loopTimer;
// Delta Time in milliseconds for navigation computations, updated with every good GPS read
static float dTnav;
//Actual navigation mode, this needed since we swith to poshold ence arrived at home
static int8_t nav_mode = NAV_MODE_NONE; //Navigation mode
static int16_t x_actual_speed = 0;
static int16_t y_actual_speed = 0;
static int32_t last_longitude = 0;
static int32_t last_latitude = 0;
static int16_t x_rate_d;
static int16_t y_rate_d;
// this is used to offset the shrinking longitude as we go towards the poles
static float GPS_scaleLonDown;
static float GPS_scaleLonUp;
// The difference between the desired rate of travel and the actual rate of travel
// updated after GPS read - 5-10hz
static int16_t x_rate_error;
static int16_t y_rate_error;
static int32_t long_error, lat_error;
// The desired bank towards North (Positive) or South (Negative)
static int16_t nav_lat;
// The desired bank towards East (Positive) or West (Negative)
static int16_t nav_lon;
//Used for rotation calculations for GPS nav vector
static float sin_yaw_y;
static float cos_yaw_x;
//Currently used WP
static int32_t GPS_WP_latitude,GPS_WP_longitude;
static uint16_t GPS_WP_altitude;
static uint8_t GPS_WP_flags;
//Actual position for calculations
static int32_t GPS_latitude,GPS_longitude;
////////////////////////////////////////////////////////////////////////////////
// Location & Navigation
////////////////////////////////////////////////////////////////////////////////
// This is the angle from the copter to the "next_WP" location in degrees * 100
static int32_t target_bearing;
// 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;
////////////////////////////////////////////////////////////////////////////////
// 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;
// distance between plane and home in cm
static int32_t home_distance;
// distance between plane and next_WP in cm
static int32_t wp_distance;
// used for slow speed wind up when start navigation;
static int16_t waypoint_speed_gov;
// this is the navigation mode what is commanded
static uint8_t GPSMode = GPSMODE_NONAV;
////////////////////////////////////////////////////////////////////////////////////
// Blink code variables
//
static uint32_t lastframe_time = 0;
static uint32_t _statusled_timer = 0;
static uint32_t _sonar_timer = 0;
static int8_t _statusled_blinks = 0;
static boolean _statusled_state = 0;
////////////////////////////////////////////////////////////////////////////////////
// moving average filter variables
//
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 int32_t GPS_lead_latitude, GPS_lead_longitude;
////////////////////////////////////////////////////////////////////////////////////
// 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);
GPS_scaleLonUp = 1.0f / cos(rads);
}
////////////////////////////////////////////////////////////////////////////////////
// Sets the waypoint to navigate, reset neccessary variables and calculate initial values
// Waypoint 16 is a virtual waypoint, it's a pos hold
void GPS_set_next_wp(uint8_t wp_number)
{
if (wp_number > 16) { return; } //Do nothing with a wrong WP number
if (wp_number <=15 ) {
GPS_WP_latitude = i2c_dataset.gps_wp[wp_number].position.lat;
GPS_WP_longitude = i2c_dataset.gps_wp[wp_number].position.lon;
GPS_WP_altitude = i2c_dataset.gps_wp[wp_number].altitude;
GPS_WP_flags = i2c_dataset.gps_wp[wp_number].flags;
i2c_dataset.status.wp_reached = 0;
} else {
GPS_WP_latitude = GPS_latitude;
GPS_WP_longitude = GPS_longitude;
GPS_WP_altitude = 0;
GPS_WP_flags = 0;
i2c_dataset.status.wp_reached = 1; //With poshold we assume that the wp is reached
}
GPS_calc_longitude_scaling(GPS_WP_latitude);
wp_distance = GPS_distance_cm(GPS_latitude,GPS_longitude,GPS_WP_latitude,GPS_WP_longitude);
target_bearing = GPS_bearing(GPS_latitude,GPS_longitude,GPS_WP_latitude,GPS_WP_longitude);
nav_bearing = target_bearing;
GPS_calc_location_error(GPS_WP_latitude,GPS_WP_longitude,GPS_latitude,GPS_longitude);
original_target_bearing = target_bearing;
waypoint_speed_gov = i2c_dataset.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
//
uint32_t GPS_distance_cm(int32_t lat1, int32_t lon1, int32_t lat2, int32_t lon2) {
float dLat = (lat2 - lat1); // difference of latitude in 1/10 000 000 degrees
float dLon = (float)(lon2 - lon1) * GPS_scaleLonDown;
float dist = sqrt(sq(dLat) + sq(dLon)) * 1.113195;
return dist;
}
////////////////////////////////////////////////////////////////////////////////////
// get bearing from pos1 to pos2, returns an 1deg = 100 precision
//
int32_t GPS_bearing(int32_t lat1, int32_t lon1, int32_t lat2, int32_t lon2)
{
float off_x = (float)lon2 - lon1;
float off_y = ((float)(lat2 - lat1)) * GPS_scaleLonUp;
float bearing = 9000.0f + atan2(-off_y, off_x) * 5729.57795f; //Convert the output redians to 100xdeg
if (bearing < 0) bearing += 36000;
return bearing;
}
////////////////////////////////////////////////////////////////////////////////////
// Calculate our current speed vector from gps position data
//
static void GPS_calc_velocity( int32_t gps_latitude, int32_t gps_longitude){
static int16_t x_speed_old = 0;
static int16_t y_speed_old = 0;
// y_GPS_speed positve = Up
// x_GPS_speed positve = Right
// initialise last_longitude and last_latitude
if( last_longitude == 0 && last_latitude == 0 ) {
last_longitude = gps_longitude;
last_latitude = gps_latitude;
}
float tmp = 1.0/dTnav;
x_actual_speed = (float)(gps_longitude - last_longitude) * GPS_scaleLonDown * tmp;
y_actual_speed = (float)(gps_latitude - last_latitude) * tmp;
#if !defined(GPS_LEAD_FILTER)
x_actual_speed = (x_actual_speed + x_speed_old) / 2;
y_actual_speed = (y_actual_speed + y_speed_old) / 2;
x_speed_old = x_actual_speed;
y_speed_old = y_actual_speed;
#endif
last_longitude = gps_longitude;
last_latitude = gps_latitude;
#if defined(GPS_LEAD_FILTER)
GPS_lead_longitude = xLeadFilter.get_position(gps_longitude,x_actual_speed);
GPS_lead_latitude = yLeadFilter.get_position(gps_latitude,y_actual_speed);
#endif
}
////////////////////////////////////////////////////////////////////////////////////
// Calculate a location error between two gps coordinates
// Becuase 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 )
{
// X Error
long_error = (float)(target_lng - gps_lng) * GPS_scaleLonDown;
// Y Error
lat_error = target_lat - gps_lat;
}
////////////////////////////////////////////////////////////////////////////////////
// Calculate nav_lat and nav_lon from the x and y error and the speed
//
static void GPS_calc_poshold(int x_error, int y_error)
{
int32_t p,i,d;
int32_t output;
int32_t x_target_speed, y_target_speed;
// East / West
x_target_speed = pi_poshold_lon.get_p(x_error); // calculate desired speed from lon error
x_rate_error = x_target_speed - x_actual_speed; // calc the speed error
p = pid_poshold_rate_lon.get_p(x_rate_error);
i = pid_poshold_rate_lon.get_i(x_rate_error + x_error, dTnav);
d = pid_poshold_rate_lon.get_d(x_error, dTnav);
d = constrain(d, -2000, 2000);
// get rid of noise
if ( (i2c_dataset.nav_flags & I2C_NAV_FLAG_LOW_SPEED_D_FILTER) && (abs(x_actual_speed) < 50)) {
d = 0;
}
output = p + i + d;
nav_lon = constrain(output, -NAV_BANK_MAX, NAV_BANK_MAX);
// North / South
y_target_speed = pi_poshold_lat.get_p(y_error); // calculate desired speed from lat error
y_rate_error = y_target_speed - y_actual_speed;
p = pid_poshold_rate_lat.get_p(y_rate_error);
i = pid_poshold_rate_lat.get_i(y_rate_error + y_error, dTnav);
d = pid_poshold_rate_lat.get_d(y_error, dTnav);
d = constrain(d, -2000, 2000);
// get rid of noise
if ( (i2c_dataset.nav_flags & I2C_NAV_FLAG_LOW_SPEED_D_FILTER) && (abs(y_actual_speed) < 50)) {
d = 0;
}
output = p + i + d;
nav_lat = constrain(output, -NAV_BANK_MAX, NAV_BANK_MAX);
// copy over I term to Nav_Rate -- if we change from poshold to RTH this will keep the wind compensation
pid_nav_lon.set_integrator(pid_poshold_rate_lon.get_integrator());
pid_nav_lat.set_integrator(pid_poshold_rate_lat.get_integrator());
}
////////////////////////////////////////////////////////////////////////////////////
// Calculate the desired nav_lat and nav_lon for distance flying such as RTH
//
static void GPS_calc_nav_rate(int max_speed)
{
// push us towards the original track
GPS_update_crosstrack();
// nav_bearing includes crosstrack
float temp = (9000l - nav_bearing) * RADX100;
// East / West
x_rate_error = (cos(temp) * max_speed) - x_actual_speed;
x_rate_error = constrain(x_rate_error, -1000, 1000);
nav_lon = pid_nav_lon.get_pid(x_rate_error, dTnav);
nav_lon = constrain(nav_lon, -NAV_BANK_MAX, NAV_BANK_MAX);
// North / South
y_rate_error = (sin(temp) * max_speed) - y_actual_speed;
y_rate_error = constrain(y_rate_error, -1000, 1000); // added a rate error limit to keep pitching down to a minimum
nav_lat = pid_nav_lat.get_pid(y_rate_error, dTnav);
nav_lat = constrain(nav_lat, -NAV_BANK_MAX, NAV_BANK_MAX);
// copy over I term to poshold_rate - So when arriving and entering to poshold we will have the wind compensation
pid_poshold_rate_lon.set_integrator(pid_nav_lon.get_integrator());
pid_poshold_rate_lat.set_integrator(pid_nav_lat.get_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 * (float)((float)i2c_dataset.nav_crosstrack_gain/100.0f)); // 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 int16_t GPS_calc_desired_speed(int16_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, i2c_dataset.nav_speed_min); // go at least 100cm/s
}
// limit the ramp up of the speed
// waypoint_speed_gov is reset to NAV_MIN_SPEED 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;
}
////////////////////////////////////////////////////////////////////////////////////
// Resets all GPS nev parameters and clears up the PID controllers. Prepares for a restarted poshold/navigation
//
void GPS_reset_nav()
{
pi_poshold_lat.reset_I();
pi_poshold_lon.reset_I();
pid_poshold_rate_lon.reset_I();
pid_poshold_rate_lat.reset_I();
pid_nav_lon.reset_I();
pid_nav_lat.reset_I();
nav_lon = 0;
nav_lat = 0;
}
////////////////////////////////////////////////////////////////////////////////////
// Update i2c_dataset from navigation output
//
void GPS_update_i2c_dataset()
{
i2c_dataset.nav_lat = nav_lat;
i2c_dataset.nav_lon = nav_lon;
i2c_dataset.wp_distance = wp_distance;
i2c_dataset.wp_target_bearing = target_bearing;
i2c_dataset.nav_bearing = nav_bearing;
}
////////////////////////////////////////////////////////////////////////////////////
// Utilities
//
int32_t wrap_18000(int32_t error)
{
if (error > 18000) error -= 36000;
if (error < -18000) error += 36000;
return error;
}
int32_t wrap_36000(int32_t angle)
{
if (angle > 36000) angle -= 36000;
if (angle < 0) angle += 36000;
return angle;
}
#if defined(NMEA)
/* The latitude or longitude is coded this way in NMEA frames
dddmm.mmmm coded as degrees + minutes + minute decimal
This function converts this format in a unique unsigned long where 1 degree = 10 000 000
I 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
*/
#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;
// 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 (int i = 0; i < 4; i++) {
frac_min *= 10;
if (isdigit(*q))
frac_min += *q++ - '0';
}
}
return deg * 10000000UL + (min * 1000000UL + frac_min*100UL) / 6;
}
/* This is am expandable 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, GSA and RMC frames to decode on the serial bus
Using the following data :
GGA
- time
- latitude
- longitude
- GPS fix
- GPS num sat (5 is enough to be +/- reliable)
- GPS alt
GSA
- 3D fix (it could be left out since we have a 3D fix if we have more than 4 sats
RMC
- GPS speed over ground, it will be handy for wind compensation (future)
*/
#define NO_FRAME 0
#define GPGGA_FRAME 1
#define GPGSA_FRAME 2
#define GPRMC_FRAME 3
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, gps_frame = NO_FRAME;
switch (c) {
case '$': param = 0; offset = 0; parity = 0;
break;
case ',':
case '*': string[offset] = 0;
if (param == 0) { //frame identification
gps_frame = NO_FRAME;
if (string[0] == 'G' && string[1] == 'P' && string[2] == 'G' && string[3] == 'G' && string[4] == 'A') gps_frame = GPGGA_FRAME;
if (string[0] == 'G' && string[1] == 'P' && string[2] == 'G' && string[3] == 'S' && string[4] == 'A') gps_frame = GPGSA_FRAME;
if (string[0] == 'G' && string[1] == 'P' && string[2] == 'R' && string[3] == 'M' && string[4] == 'C') gps_frame = GPRMC_FRAME;
}
switch (gps_frame)
{
//************* GPGGA FRAME parsing
case GPGGA_FRAME:
switch (param)
{
case 1: i2c_dataset.time = (atof(string)*1000); //up to .000 s precision not needed really but the data is there anyway
break;
//case 2: i2c_dataset.gps_loc.lat = GPS_coord_to_degrees(string);
case 2: GPS_read[LAT] = GPS_coord_to_degrees(string);
break;
//case 3: if (string[0] == 'S') i2c_dataset.gps_loc.lat = -i2c_dataset.gps_loc.lat;
case 3: if (string[0] == 'S') GPS_read[LAT] = -GPS_read[LAT];
break;
//case 4: i2c_dataset.gps_loc.lon = GPS_coord_to_degrees(string);
case 4: GPS_read[LON] = GPS_coord_to_degrees(string);
break;
//case 5: if (string[0] == 'W') i2c_dataset.gps_loc.lon = -i2c_dataset.gps_loc.lon;
case 5: if (string[0] == 'W') GPS_read[LON] = -GPS_read[LON];
break;
case 6: i2c_dataset.status.gps2dfix = string[0] > '0';
break;
case 7: i2c_dataset.status.numsats = atoi(string);
break;
case 9: i2c_dataset.altitude = atoi(string);
break;
}
break;
//************* GPGSA FRAME parsing
case GPGSA_FRAME:
switch (param)
{
case 2: i2c_dataset.status.gps3dfix = string[0] == '3';
break;
}
break;
//************* GPGSA FRAME parsing
case GPRMC_FRAME:
switch(param)
{
case 7: i2c_dataset.ground_speed = (atof(string)*0.5144444)*10; //convert to m/s*100
break;
case 8: i2c_dataset.ground_course = (atof(string)*10); //Convert to degrees *10 (.1 precision)
break;
}
break;
}
param++; offset = 0;
if (c == '*') checksum_param=1;
else parity ^= c;
break;
case '\r':
case '\n':
if (checksum_param) { //parity checksum
uint8_t checksum = 16 * ((string[0]>='A') ? string[0] - 'A'+10: string[0] - '0') + ((string[1]>='A') ? string[1] - 'A'+10: string[1]-'0');
if (checksum == parity) frameOK = 1;
}
checksum_param=0;
break;
default:
if (offset < 15) string[offset++] = c;
if (!checksum_param) parity ^= c;
}
return frameOK && (gps_frame == GPGGA_FRAME);
}
#endif
#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_status {
uint32_t time; // GPS msToW
uint8_t fix_type;
uint8_t fix_status;
uint8_t differential_status;
uint8_t res;
uint32_t time_to_first_fix;
uint32_t uptime; // milliseconds
};
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;
uint32_t res2;
};
struct ubx_nav_velned {
uint32_t time; // GPS msToW
int32_t ned_north;
int32_t ned_east;
int32_t ned_down;
uint32_t speed_3d;
uint32_t speed_2d;
int32_t heading_2d;
uint32_t speed_accuracy;
uint32_t heading_accuracy;
};
enum ubs_protocol_bytes {
PREAMBLE1 = 0xb5,
PREAMBLE2 = 0x62,
CLASS_NAV = 0x01,
CLASS_ACK = 0x05,
CLASS_CFG = 0x06,
MSG_ACK_NACK = 0x00,
MSG_ACK_ACK = 0x01,
MSG_POSLLH = 0x2,
MSG_STATUS = 0x3,
MSG_SOL = 0x6,
MSG_VELNED = 0x12,
MSG_CFG_PRT = 0x00,
MSG_CFG_RATE = 0x08,
MSG_CFG_SET_RATE = 0x01,
MSG_CFG_NAV_SETTINGS = 0x24
};
enum ubs_nav_fix_type {
FIX_NONE = 0,
FIX_DEAD_RECKONING = 1,
FIX_2D = 2,
FIX_3D = 3,
FIX_GPS_DEAD_RECKONING = 4,
FIX_TIME = 5
};
enum ubx_nav_status_bits {
NAV_STATUS_FIX_VALID = 1
};
// Packet checksum accumulators
static uint8_t _ck_a;
static uint8_t _ck_b;
// State machine state
static uint8_t _step;
static uint8_t _msg_id;
static uint16_t _payload_length;
static uint16_t _payload_counter;
static bool next_fix;
static uint8_t _class;
// do we have new position information?
static bool _new_position;
// do we have new speed information?
static bool _new_speed;
static uint8_t _disable_counter;
// Receive buffer
static union {
ubx_nav_posllh posllh;
ubx_nav_status status;
ubx_nav_solution solution;
ubx_nav_velned velned;
uint8_t bytes[];
} _buffer;
void _update_checksum(uint8_t *data, uint8_t len, uint8_t &ck_a, uint8_t &ck_b)
{
while (len--) {
ck_a += *data;
ck_b += ck_a;
data++;
}
}
bool GPS_UBLOX_newFrame(uint8_t data)
{
bool parsed = false;
switch(_step) {
case 1:
if (PREAMBLE2 == data) {
_step++;
break;
}
_step = 0;
case 0:
if(PREAMBLE1 == data) _step++;
break;
case 2:
_step++;
_class = data;
_ck_b = _ck_a = data; // reset the checksum accumulators
break;
case 3:
_step++;
_ck_b += (_ck_a += data); // checksum byte
_msg_id = data;
break;
case 4:
_step++;
_ck_b += (_ck_a += data); // checksum byte
_payload_length = data; // payload length low byte
break;
case 5:
_step++;
_ck_b += (_ck_a += data); // checksum byte
_payload_length += (uint16_t)(data<<8);
if (_payload_length > 512) {
_payload_length = 0;
_step = 0;
}
_payload_counter = 0; // prepare to receive payload
break;
case 6:
_ck_b += (_ck_a += data); // checksum byte
if (_payload_counter < sizeof(_buffer)) {
_buffer.bytes[_payload_counter] = data;
}
if (++_payload_counter == _payload_length)
_step++;
break;
case 7:
_step++;
if (_ck_a != data) _step = 0; // bad checksum
break;
case 8:
_step = 0;
if (_ck_b != data) break; // bad checksum
if (UBLOX_parse_gps()) { parsed = true; }
} //end switch
return parsed;
}
bool UBLOX_parse_gps(void)
{
switch (_msg_id) {
case MSG_POSLLH:
i2c_dataset.time = _buffer.posllh.time;
GPS_read[LON] = _buffer.posllh.longitude;
GPS_read[LAT] = _buffer.posllh.latitude;
i2c_dataset.altitude = _buffer.posllh.altitude_msl / 10 /100; //alt in m
i2c_dataset.status.gps3dfix = next_fix;
_new_position = true;
break;
case MSG_STATUS:
next_fix = (_buffer.status.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.status.fix_type == FIX_3D);
if (!next_fix) i2c_dataset.status.gps3dfix = false;
break;
case MSG_SOL:
next_fix = (_buffer.solution.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.solution.fix_type == FIX_3D);
if (!next_fix) i2c_dataset.status.gps3dfix = false;
i2c_dataset.status.numsats = _buffer.solution.satellites;
//GPS_hdop = _buffer.solution.position_DOP;
//debug[3] = GPS_hdop;
break;
case MSG_VELNED:
//speed_3d = _buffer.velned.speed_3d; // cm/s
i2c_dataset.ground_speed = _buffer.velned.speed_2d; // cm/s
i2c_dataset.ground_course = (uint16_t)(_buffer.velned.heading_2d / 10000); // Heading 2D deg * 100000 rescaled to deg * 10
_new_speed = true;
break;
default:
return false;
}
// we only return true when we get new position and speed data
// this ensures we don't use stale data
if (_new_position && _new_speed) {
_new_speed = _new_position = false;
return true;
}
return false;
}
#endif //UBLOX
#if defined(MTK)
struct diyd_mtk_msg {
int32_t latitude;
int32_t longitude;
int32_t altitude;
int32_t ground_speed;
int32_t ground_course;
uint8_t satellites;
uint8_t fix_type;
uint32_t utc_date;
uint32_t utc_time;
uint16_t hdop;
};
// #pragma pack(pop)
enum diyd_mtk_fix_type {
FIX_NONE = 1,
FIX_2D = 2,
FIX_3D = 3
};
enum diyd_mtk_protocol_bytes {
PREAMBLE1 = 0xd0,
PREAMBLE2 = 0xdd,
};
// Packet checksum accumulators
uint8_t _ck_a;
uint8_t _ck_b;
// State machine state
uint8_t _step;
uint8_t _payload_counter;
// Time from UNIX Epoch offset
long _time_offset;
bool _offset_calculated;
// Receive buffer
union {
diyd_mtk_msg msg;
uint8_t bytes[];
} _buffer;