-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathmain.cpp
1561 lines (1330 loc) · 45.8 KB
/
main.cpp
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
//
// Created by Cooper Grill on 3/31/2020.
//
// Arduino libraries
#include <Arduino.h>
#include <Wire.h>
#include <SPI.h>
#include <due_can.h>
#include <AccelStepper.h>
#include <SPIMemory.h>
// Internal libraries
#include "IMU.h"
#include "Indicator.h"
#include "StateMachine.h"
#include "StateColors.h"
#include "CANOpen.h"
#include "TorqueMotor.h"
#include "DriveMotor.h"
#include "Controller.h"
#include "PIDController.h"
#include "FSFController.h"
#include "KalmanFilter.h"
#include "BikeModel.h"
#include "Encoder.h"
#include "ZSS.h"
#include "Compass.h"
// States
#define IDLE 0
#define CALIB 1
#define MANUAL 2
#define ASSIST 3
#define AUTO 4
#define FALLEN 5
#define E_STOP 6
// User request bit flags
#define R_CALIB_MODE 0b00000001U
#define R_MANUAL 0b00000010U
#define R_STOP 0b00000100U
#define R_RESUME 0b00001000U
#define R_TIMEOUT 0b00010000U
#define R_CALIB_GYRO 0b00100000U
#define R_CALIB_ACCEL 0b01000000U
#define R_CALIB_VARIANCE 0b10000000U
#define R_CALIB_TILT 0b0000000100000000U
#define R_RETRACT_ZSS 0b0000001000000000U
#define R_DEPLOY_ZSS 0b0000010000000000U
#define R_CALIB_TORQUE 0b0000100000000000U
// Info for torque motor
#define TM_NODE_ID 127
#define TM_CURRENT_MAX 1000
#define TM_TORQUE_MAX 1000
#define TM_TORQUE_SLOPE 10000 // Thousandths of max torque per second
// State transition constants
#define FTHRESH (PI * 38.0/180.0) // Threshold for being fallen over
#define UTHRESH (PI/20.0) // Threshold for being back upright
#define HIGH_V_THRESH 4.2 // Velocity threshold at which to enter automatic mode (torque control)
#define LOW_V_THRESH 3.3 // Velocity threshold at which to leave automatic mode (torque control)
#define OVERSTEER_THRESH (PI/3.0) // Threshold for steering angle before initiating E_STOP
// Loop timing constants (frequencies in Hz)
#define REPORT_UPDATE_FREQ 10
#define STORE_UPDATE_FREQ 100
#define REQUIRE_ACTUATORS
//#define RADIOCOMM
//#define HEADING_CONTROL
//#define KALMAN_CALIB
//#define COMPASS_ENABLED
//#define GPS_ENABLED
//#define INSPECT_TIME
#define DEMO_MODE
#ifdef GPS_ENABLED
#define GPSSerial Serial3 // Hardware serial port to talk to GPS
#include <Adafruit_GPS.h>
#endif
#ifdef RADIOCOMM
//#include <nRF24L01.h>
#include <RF24.h>
RF24 radio(7, 8);
#define TELEMETRY radio
uint8_t readAddr[] = "UNODE";
uint8_t writeAddr[] = "DNODE";
#else
#define TELEMETRY Serial
#endif
// Device object definitions
IMU imu(2);
Indicator indicator(3, 4, 5, 11, 22);
TorqueMotor *torque_motor;
DriveMotor *drive_motor;
Encoder encoder(16, 17);
SPIFlash flash(6);
#ifdef GPS_ENABLED
Adafruit_GPS gps(&GPSSerial);
#endif
#ifdef COMPASS_ENABLED
Compass compass;
#endif
#define K_HEADING 0.1
#define DEL_R_MAX 0.21
BikeModel bike_model;
KalmanFilter<4, 4, 2> orientation_filter;
#ifdef GPS_ENABLED
KalmanFilter<2, 2, 1> heading_filter;
KalmanFilter<4, 4, 2, double> position_filter;
#else
KalmanFilter<2, 1, 1> heading_filter;
KalmanFilter<4, 2, 2, double> position_filter;
#endif
Controller *controller;
// State variables
uint16_t user_req = 0; // User request binary flags
uint8_t state = IDLE;
float dt;
float phi = 0.0; // Roll angle (rad)
float del = 0.0; // Steering angle (rad)
float dphi = 0.0; // Roll angle rate (rad/s)
float ddel = 0.0; // Steering angle rate (rad/s)
float phi_y = 0.0; // Roll angle measurement (rad)
float del_y = 0.0; // Steering angle measurement (rad)
float dphi_y = 0.0; // Roll angle rate measurement (rad/s)
float ddel_y = 0.0; // Steering angle rate measurement (rad/s)
float v = 0.0; // Velocity (m/s)
bool free_running = false; // Is rotation constrained by the ZSS being deployed?
float heading = 0.0; // Heading relative to true north (rad)
float dheading = 0.0; // Rate of heading change (rad/s)
float heading_y = 270.0 / 180.0 * PI; // Heading magnetometer measurement (rad)
float dheading_y = 0.0; // Rate of heading change gyroscope measurement (rad/s)
double lat = 0.0; // Latitude (deg)
double lon = 0.0; // Longitude (deg)
double dlat = 0.0; // Rate of latitude change (deg/s)
double dlon = 0.0; // Rate of longitude change (deg/s)
double lat_y = 0.0; // Latitude GPS measurement (deg)
double lon_y = 0.0; // Longitude GPS measurement (deg)
// Reference variables
float phi_r = 0.0; // Required roll angle (rad)
float del_r = 0.0; // Required steering angle (rad)
float v_r = 0.0; // Required velocity (m/s)
float heading_r = 270.0 / 180.0 * PI; // Required heading (rad)
// Control variables
float u = 0.0; // Control commanded torque (Nm)
float torque = 0.0; // Current torque (Nm)
// Filter tuning parameters
float var_roll_accel = 0.58; // Variance in (rad/s^2)^2
float var_steer_accel = 0.58; // Variance in (rad/s^2)^2
float var_heading = 0.01; // Variance in (rad/s^2)^2
const int enPin = A0; // Information for brake stepper
const int dirPin = A2;
const int stepPin = A1;
AccelStepper stepper(AccelStepper::DRIVER, stepPin, dirPin);
ZSS zss(28, 26);
void report();
void home_delta();
void find_variances(float &var_v, float &var_a, float &var_phi, float &var_del, float &var_dphi, float &var_ddel);
void storeTelemetry();
void retrieveTelemetry();
void clearTelemetry();
void record_current_parameters();
void physical_brake(bool engage);
void reset_filters();
bool isRecording = false;
#define PARAMETER_ADDR 0x000000
#define TELEMETRY_ADDR 0x001000
#define FLASH_SIZE 2097152
#define SECTOR_SIZE 4096
#define PAGE_SIZE 256
struct __attribute__((__packed__)) StoredParameters {
float var_v, var_a, var_phi, var_del, var_dphi, var_ddel;
int16_t ax_off, ay_off, az_off, gx_off, gy_off, gz_off;
float imu_tilt;
uint32_t zss_a1_offset, zss_a2_offset;
uint16_t radio_channel;
} parameters;
struct __attribute__((__packed__)) TelemetryFrame {
uint8_t state;
float time, phi, del, dphi, ddel, v_r, v, u, torque, heading, dheading, phi_y, del_y, dphi_y,
ddel_y, heading_y, dheading_y, phi_r, del_r, heading_r;
double lat, lon, dlat, dlon, lat_y, lon_y;
} t_frame;
static uint32_t storeAddress = TELEMETRY_ADDR;
void printTelemetryFrame(TelemetryFrame &telemetryFrame);
#define FRAMES_PER_PAGE (PAGE_SIZE / (sizeof t_frame))
struct TelemetryFramePage {
TelemetryFrame frames[FRAMES_PER_PAGE];
} t_frame_page;
struct SteeringCommand {
struct SteeringCommand *next;
float delta;
unsigned long time;
} *head, *tail;
// ISRs
void countPulse() {
encoder.countPulse();
}
long mstart = -1;
static unsigned long last_time;
void setup() {
Wire.begin(); // Begin I2C interface
SPI.begin(); // Begin Serial Peripheral Interface (SPI)
Serial.begin(115200); // Begin Main Serial (UART to USB) communication
flash.begin(); // Begin SPI comm to flash memory
Serial.println("Loading parameters from Flash.");
// Load parameters from Flash
if (flash.readAnything(PARAMETER_ADDR, parameters)) {
Serial.println("Loaded parameters from FLash.");
Serial.println(parameters.imu_tilt);
} else {
Serial.print("Failed to load parameters from Flash, error code: 0x");
Serial.println(flash.error(), HEX);
}
if (parameters.zss_a1_offset == 0xFFFFFFFF || parameters.zss_a2_offset == 0xFFFFFFFF) {
parameters.zss_a1_offset = 1260;
parameters.zss_a2_offset = 1430;
}
Serial.print(parameters.zss_a1_offset);
Serial.print('\t');
Serial.println(parameters.zss_a2_offset);
zss.start(parameters.zss_a1_offset, parameters.zss_a2_offset); // Initial state is deployed
#ifdef RADIOCOMM
if (!radio.begin()) {
Serial.println("Radio not found");
while (true);
}
radio.openWritingPipe(writeAddr);
radio.openReadingPipe(1, readAddr);
radio.setPALevel(RF24_PA_MAX);
radio.setChannel(parameters.radio_channel);
radio.startListening();
#endif
Can0.begin(CAN_BPS_1000K); // Begin 1M baud rate CAN interface, no enable pin
Can0.watchFor(); // Watch for all incoming CAN-Bus messages
analogWriteResolution(12); // Enable expanded PWM and ADC resolution
analogReadResolution(12);
stepper.setAcceleration(2000.0);
stepper.setMaxSpeed(1000.0);
// Initialize indicator
indicator.start();
indicator.beep(100);
indicator.setPassiveRGB(RGB_STARTUP_P);
indicator.setBlinkRGB(RGB_STARTUP_B);
#ifdef REQUIRE_ACTUATORS
// Initialize torque control motor
torque_motor = new TorqueMotor(&Can0, TM_NODE_ID, TM_CURRENT_MAX, TM_TORQUE_MAX, TM_TORQUE_SLOPE,
8 * PI, 16 * PI, 10);
torque_motor->start();
Serial.println("Initialized Torque Motor.");
Serial.println("Initializing Drive Motor.");
// Initialize Bafang drive motor
DRIVE_SERIAL.begin(1200); // Begin Bafang Serial (UART) communication
Serial.println("Waiting for Drive Motor.");
delay(1000);
drive_motor = new DriveMotor(DAC0);
drive_motor->start();
Serial.println("Initialized Drive Motor.");
#endif
imu.start(); // Initialize IMU
imu.configure(2, 2, 3, parameters.imu_tilt); // Set accelerometer and gyro resolution, on-chip low-pass filter
imu.set_accel_offsets(parameters.ax_off, parameters.ay_off, parameters.az_off);
imu.set_gyro_offsets(parameters.gx_off, parameters.gy_off, parameters.gz_off);
#ifdef GPS_ENABLED
// Initialize GPS
Serial.println("Initializing GPS.");
gps.begin(9600); // 9600 NMEA is the default baud rate
// comment/uncomment lines to change baud rate
gps.sendCommand("$PMTK251,57600*2C"); // set baud rate to 57600
GPSSerial.end();
delay(1000);
gps.begin(57600); // must match what's chosen earlier
gps.sendCommand(PMTK_SET_NMEA_OUTPUT_RMCONLY); // turn on RMC (recommended minimum)
// GPS.sendCommand(PMTK_SET_NMEA_OUTPUT_RMCGGA); // turn on RMC (recommended minimum) and GGA (fix data) including altitude
gps.sendCommand(PMTK_SET_NMEA_UPDATE_10HZ); // 1 Hz recommended, 10 Hz max for 9600 baud/RMCONLY
delay(1000);
Serial.println("Initialized GPS, waiting for readings.");
// Wait until we have a real GPS reading
while (true) {
gps.read();
if (gps.newNMEAreceived() && gps.parse(gps.lastNMEA())) {
lat_y = gps.latitudeDegrees;
lon_y = gps.longitudeDegrees;
if (lat_y != 0.0 && lon_y != 0.0)
break;
}
}
Serial.println("Initialized GPS, readings confirmed.");
#endif
#ifdef COMPASS_ENABLED
// Initialize magnetometer
Serial.println("Initializing compass.");
compass.start();
compass.rotation = imu.rotation;
Serial.println("Initialized compass.");
#endif
//! Temporary sensor covariance overriding parameters
parameters.var_v = 0.0004;
parameters.var_a = 0.02;
parameters.var_phi = 0.00002629879368; // From averaging data
parameters.var_del = 0.00001;
parameters.var_dphi = 0.0000002117716535; // From averaging data
parameters.var_ddel = 0.01;
Serial.println("Initializing controller.");
// Initialize stability controller
controller = new FSFController(&bike_model, 18.0, -6, -7, -8, -9);
Serial.println("Initialized controller.");
Serial.println("Initializing Kalman filters.");
// Initialize local orientation Kalman filter
orientation_filter.x = {0, 0, 0, 0}; // Initial state estimate
orientation_filter.P = BLA::Identity<4, 4>() * 0.1; // Initial estimate covariance
orientation_filter.C = BLA::Identity<4, 4>(); // Sensor matrix
orientation_filter.R = { // Sensor covariance matrix
parameters.var_phi, 0, 0, 0,
0, parameters.var_del, 0, 0,
0, 0, parameters.var_dphi, 0,
0, 0, 0, parameters.var_ddel
};
float var_gyro_z = 0.01;
// Initialize heading Kalman filter
heading_filter.x = {270.0 / 180.0 * PI, 0}; // Initial state estimate
heading_filter.P = BLA::Identity<2, 2>() * 0.1; // Initial estimate covariance
heading_filter.B = {0, 1};
#ifdef GPS_ENABLED
heading_filter.C = BLA::Identity<2, 2>(); // Sensor matrix
heading_filter.R = { // Sensor covariance matrix
0.000001, 0, // TODO: Set sensor covariances for Magnetometer/GPS
0, var_gyro_z
};
#else
heading_filter.C = {0, 1};
heading_filter.R = {
var_gyro_z
};
#endif
// Initialize position Kalman filter
position_filter.x = {lat_y, lon_y, 0, 0}; // Initial state estimate
position_filter.P = BLA::Identity<4, 4>() * 0.1; // Initial estimate covariance
position_filter.B = {0, 0,
0, 0,
1, 0,
0, 1};
#ifdef GPS_ENABLED
position_filter.C = BLA::Identity<4, 4>(); // Sensor matrix
position_filter.R = { // Sensor covariance matrix
0.00000001, 0, 0, 0, // TODO: Set sensor covariances for GPS
0, 0.00000001, 0, 0,
0, 0, 0.1, 0,
0, 0, 0, 0.1
};
#else
position_filter.C = {0, 0, 1, 0,
0, 0, 0, 1};
position_filter.R = { // Sensor covariance matrix
0.00000001, 0,
0, 0.00000001
};
#endif
Serial.println("Initialized Kalman filter.");
Serial.println("Initializing encoder and interrupts.");
encoder.start();
attachInterrupt(digitalPinToInterrupt(16), countPulse, CHANGE);
Serial.println("Initialized encoder and interrupts.");
assert_idle();
pinMode(enPin, OUTPUT);
digitalWrite(enPin, LOW);
head = tail = nullptr;
Serial.println("Finished setup.");
last_time = millis();
}
void loop() {
static unsigned long last_report_time = millis();
static unsigned long last_store_time = millis();
static unsigned long timeout = 0;
#ifdef INSPECT_TIME
unsigned long ref = micros();
#endif
bool new_gps_data = false;
dt = (float) (millis() - last_time) / 1000.0f;
last_time = millis();
// Update sensor information
imu.update();
encoder.update();
// Get current speed
v = encoder.getSpeed();
#ifdef COMPASS_ENABLED
compass.update();
#endif
#ifdef GPS_ENABLED
for (int i = 0; i < 20 && gps.available(); i++)
gps.read();
if (gps.newNMEAreceived() && gps.parse(gps.lastNMEA()))
new_gps_data = true;
#endif
#ifdef REQUIRE_ACTUATORS
torque_motor->update();
#endif
#ifdef INSPECT_TIME
Serial.print(micros() - ref);
Serial.println(" us to read sensors.");
ref = micros();
#endif
// Update heading Kalman filter parameters
heading_filter.A = {
1, dt,
0, 1
};
heading_filter.Q = {
var_heading * dt * dt, var_heading * dt,
var_heading * dt, var_heading
};
// heading_y = compass.angle;
dheading_y = imu.gyroZ() * cos(phi) + imu.gyroY() * sin(phi);
heading_filter.predict({dheading_y - dheading});
heading = heading_filter.x(0);
dheading = heading_filter.x(1);
heading_filter.x(0) = fmod(heading, (float) (2.0f * PI));
heading_filter.x(1) = fmod(dheading, (float) (2.0f * PI));
heading = heading_filter.x(0);
dheading = heading_filter.x(1);
#ifdef GPS_ENABLED
// Update if we have new GPS data and are moving fast enough
if (new_gps_data && v > 2.8) {
heading_y = gps.angle * (float) PI / 180.0f;
heading_filter.update({heading_y, dheading_y});
heading = heading_filter.x(0);
dheading = heading_filter.x(1);
heading_filter.x(0) = fmod(heading, (float) (2.0f * PI));
heading_filter.x(1) = fmod(dheading, (float) (2.0f * PI));
heading = heading_filter.x(0);
dheading = heading_filter.x(1);
}
#else
heading_filter.update({dheading_y});
heading = heading_filter.x(0);
dheading = heading_filter.x(1);
heading_filter.x(0) = fmod(heading, (float) (2.0f * PI));
heading_filter.x(1) = fmod(dheading, (float) (2.0f * PI));
#endif
#ifdef INSPECT_TIME
Serial.print(micros() - ref);
Serial.println(" us to Kalman filter heading.");
ref = micros();
#endif
// Update orientation state measurement
float g_mag = imu.accelY() * imu.accelY() +
imu.accelZ() * imu.accelZ(); // Check if measured orientation gravity vector exceeds feasibility
phi_y = (g_mag <= 10.0f * 10.0f || g_mag >= 6.0f * 6.0f) ? atan2(-imu.accelY(), imu.accelZ()) : phi_y;
dphi_y = -imu.gyroX();
#ifdef REQUIRE_ACTUATORS
del_y = torque_motor->getPosition();
ddel_y = torque_motor->getVelocity();
torque = torque_motor->getTorque();
#endif
// Update orientation Kalman filter parameters
orientation_filter.A = bike_model.kalmanTransitionMatrix(v, dt, free_running);
orientation_filter.B = bike_model.kalmanControlsMatrix(v, dt, free_running);
BLA::Matrix<4, 1, Array<4, 1>> w_orr = {0.5f * var_roll_accel * dt * dt,
0.5f * var_steer_accel * dt * dt,
var_roll_accel * dt,
var_steer_accel * dt};
orientation_filter.Q = w_orr * (~w_orr);
// Update orientation state estimate
orientation_filter.predict({0, torque});
orientation_filter.update({phi_y, del_y, dphi_y, ddel_y});
phi = orientation_filter.x(0);
orientation_filter.x(1) = del_y;
del = orientation_filter.x(1);
dphi = orientation_filter.x(2);
orientation_filter.x(3) = ddel_y;
ddel = orientation_filter.x(3);
#ifdef INSPECT_TIME
Serial.print(micros() - ref);
Serial.println(" us to Kalman filter orientation.");
ref = micros();
#endif
#ifdef HEADING_CONTROL
// Calculate steering setpoint based on heading error
float e_heading = heading_r - heading;
if (e_heading > PI)
e_heading -= (float) (2.0 * PI);
else if (e_heading < -PI)
e_heading += (float) (2.0 * PI);
if (state == AUTO) {
del_r = constrain(K_HEADING * e_heading, -DEL_R_MAX, DEL_R_MAX);
} else if (state == ASSIST) {
del_r = constrain(0.5 * e_heading, -4 * DEL_R_MAX, 4 * DEL_R_MAX);
}
#endif
#ifdef INSPECT_TIME
Serial.print(micros() - ref);
Serial.println(" us to set steering from heading.");
ref = micros();
#endif
//#ifdef DEMO_MODE
// del_r = constrain(3*phi, -5 * DEL_R_MAX, 5 * DEL_R_MAX);
//#endif
// Update indicator
indicator.update();
// Act based on machine state, transition if necessary
switch (state) {
case IDLE: // Idle
// Transitions
if (fabs(phi) > FTHRESH)
assert_fallen();
if (v > 0.6 || v_r > 0) {
while (!torque_motor->switchOn());
assert_assist();
while (!torque_motor->enableOperation());
}
if (user_req & R_CALIB_MODE)
assert_calibrate();
if (user_req & R_MANUAL)
assert_manual();
if (user_req & R_STOP)
assert_emergency_stop();
// Action
idle();
break;
case CALIB: // Sensor calibration
// Transitions
if (user_req & R_RESUME) {
user_req &= ~R_CALIB_MODE;
assert_idle();
}
// Action
calibrate();
break;
case MANUAL: // Manual operation
// Transitions
if (user_req & R_RESUME) {
user_req &= ~(R_RESUME | R_MANUAL);
assert_idle();
}
// Action
manual();
break;
case ASSIST: // Assisted (training wheel) motion, only control heading
// Transitions
if (fabs(phi) > FTHRESH)
assert_fallen();
if (v > HIGH_V_THRESH && v_r > HIGH_V_THRESH && millis() - mstart > 1000)
assert_automatic();
if (v < 0.05 && v_r == 0)
assert_idle();
if (user_req & R_STOP)
assert_emergency_stop();
// Action
assist();
break;
case AUTO: // Automatic motion, control heading and stability
// Transitions
if (fabs(phi) > FTHRESH)
assert_fallen();
if (v < LOW_V_THRESH)
assert_assist();
if (user_req & R_STOP)
assert_emergency_stop();
if (fabs(del) > OVERSTEER_THRESH)
assert_emergency_stop();
// Action
automatic();
break;
case FALLEN: // Fallen
// Transitions
if (fabs(phi) < UTHRESH)
assert_idle();
// Action
fallen();
break;
case E_STOP: // Emergency stop
// Transitions
if (fabs(phi) > FTHRESH)
assert_fallen();
if (user_req & R_RESUME) {
user_req &= ~(R_RESUME | R_STOP);
assert_idle();
}
// Action
emergency_stop();
break;
default: // Invalid state, fatal error
indicator.setPassiveRGB(0, 0, 0);
break;
}
#ifdef INSPECT_TIME
Serial.print(micros() - ref);
Serial.println(" us to perform state action and transitions.");
ref = micros();
#endif
// Compute rate of latitude and longitude change given speed and heading estimate
dlat = v * cos(heading) * MPS_2_DEGLATPS; // Convert northward speed to degrees of latitude per second
dlon = v * sin(heading) * MPS_2_DEGLONPS(lat); // Convert east-west speed to degrees of longitude per second.
// (Conversion is latitude dependent.)
// Update position Kalman filter parameters
position_filter.A = {
1, 0, dt, 0,
0, 1, 0, dt,
0, 0, 1, 0,
0, 0, 0, 1
};
BLA::Matrix<4, 1, Array<4, 1, double>> w_pos = {0.5 * 0.2 * dt * dt,
0.5 * 0.2 * dt * dt,
0.2 * dt,
0.2 * dt}; // MAGIC 0.2 guess
position_filter.Q = w_pos * (~w_pos);
#ifdef GPS_ENABLED
position_filter.predict({dlat - position_filter.x(2), dlon - position_filter.x(3)});
position_filter.x(2) = dlat;
position_filter.x(3) = dlon;
// Only update if we have new GPS readings
if (new_gps_data) {
lat_y = gps.latitudeDegrees;
lon_y = gps.longitudeDegrees;
position_filter.update({lat_y, lon_y, dlat, dlon});
}
#else
position_filter.predict({dlat - position_filter.x(2), dlon - position_filter.x(3)});
position_filter.update({dlat, dlon});
#endif
lat = position_filter.x(0);
lon = position_filter.x(1);
#ifdef INSPECT_TIME
Serial.print(micros() - ref);
Serial.println(" us to Kalman filter position.");
ref = micros();
#endif
if ((user_req & R_TIMEOUT) && !zss.deploying && millis() + ZSS_DEPLOY_MS > timeout) {
zss.deploy();
}
if ((user_req & R_TIMEOUT) && millis() > timeout) {
user_req &= ~R_TIMEOUT;
#ifdef REQUIRE_ACTUATORS
if (state == AUTO) {
torque_motor->setTorque(0);
assert_assist();
}
v_r = 0;
drive_motor->setSpeed(0);
#endif
}
if (mstart > 0 && head != nullptr && millis() - mstart >= head->time) {
#ifdef HEADING_CONTROL
heading_r = head->delta;
#else
// del_r = head->delta;
#endif
auto temp = head;
head = head->next;
free(temp);
if (head == nullptr)
tail = nullptr;
}
// Store telemetry for current frame
if (millis() - last_store_time >= 1000 / STORE_UPDATE_FREQ && isRecording) {
storeTelemetry();
last_store_time = millis();
}
// Report state, reference, and control values
if (millis() - last_report_time >= 1000 / REPORT_UPDATE_FREQ) {
// Don't report over radio if we are running
#ifdef RADIOCOMM
if (!isRecording)
report();
#else
// report();
#endif
last_report_time = millis();
}
#ifdef INSPECT_TIME
Serial.print(micros() - ref);
Serial.println(" us to process time-based triggers.");
ref = micros();
#endif
#ifdef RADIOCOMM
uint8_t pipenum;
if (TELEMETRY.available(&pipenum)) {
if (pipenum == 1) {
uint8_t buffer[32];
TELEMETRY.read(buffer, 32);
uint8_t c = buffer[0];
Serial.print(c);
Serial.println(buffer[1]);
switch (c) {
case 'v':
v_r = *((float *) &(buffer[2]));
drive_motor->setSpeed(v_r);
break;
case 'd':
del_r = *((float *) &(buffer[2]));
break;
case 'h':
heading_r = *((float *) &(buffer[2]));
break;
case 'c':
user_req = *((uint16_t *) &(buffer[2]));
break;
case 't':
v_r = *((float *) &(buffer[2]));
mstart = millis() + 5000; // start in 5s
timeout = mstart + *((uint32_t *) &(buffer[6]));
user_req |= R_TIMEOUT;
break;
case 'r':
isRecording = true;
break;
case 's':
isRecording = false;
break;
case 'q':
if (head == nullptr) {
head = tail = new struct SteeringCommand;
head->delta = *((float *) &(buffer[2]));
head->time = *((uint32_t *) &(buffer[6]));
head->next = nullptr;
} else {
auto *new_command = new struct SteeringCommand;
new_command->delta = *((float *) &(buffer[2]));
new_command->time = *((uint32_t *) &(buffer[6]));
new_command->next = nullptr;
tail->next = new_command;
tail = new_command;
}
break;
default:
break;
}
}
}
#endif
if (Serial.available()) {
uint8_t c = Serial.read();
switch (c) {
case 'v':
v_r = Serial.parseFloat();
#ifdef REQUIRE_ACTUATORS
drive_motor->setSpeed(v_r);
#endif
break;
case 'd':
del_r = Serial.parseFloat();
break;
case 'h':
heading_r = Serial.parseFloat();
break;
case 'c':
user_req |= Serial.parseInt();
break;
case 't':
v_r = Serial.parseFloat();
mstart = millis() + 500; // wait 5s
timeout = mstart + Serial.parseInt();
user_req |= R_TIMEOUT;
break;
case 'f':
retrieveTelemetry();
break;
case 'r':
isRecording = true;
break;
case 's':
isRecording = false;
break;
case 'q':
if (head == nullptr) {
head = tail = new struct SteeringCommand;
head->delta = Serial.parseFloat();
head->time = Serial.parseInt();
head->next = nullptr;
} else {
auto *new_command = new struct SteeringCommand;
new_command->delta = Serial.parseFloat();
new_command->time = Serial.parseInt();
new_command->next = nullptr;
tail->next = new_command;
tail = new_command;
}
break;
case 'z':
clearTelemetry();
break;
case 'w':
zss.adjustOffsets(Serial.parseInt(), Serial.parseInt());
parameters.zss_a1_offset = zss.a1_offset;
parameters.zss_a2_offset = zss.a2_offset;
record_current_parameters();
break;
case 'k':
parameters.radio_channel = Serial.parseInt();
#ifdef RADIOCOMM
radio.stopListening();
radio.setChannel(parameters.radio_channel);
radio.startListening();
#endif
record_current_parameters();
break;
default:
break;
}
while (Serial.available() > 0)
Serial.read();
indicator.boop(100);
}
if (mstart > 0 && millis() > mstart && v_r > 0) { //} && !isRecording) {
Serial.println("We're going!");
isRecording = true;
#ifdef REQUIRE_ACTUATORS
drive_motor->setSpeed(v_r);
#endif
}
#ifdef INSPECT_TIME
Serial.print(micros() - ref);
Serial.println(" us to process commands.");
ref = micros();
#endif
// Run stepper and ZSS
stepper.run();
zss.run();
#ifdef INSPECT_TIME
Serial.print(micros() - ref);
Serial.println(" us to run stepper and ZSS.");
ref = micros();
#endif
}
void idle() {
if (user_req & R_RETRACT_ZSS) {
zss.retract();
user_req = user_req & ~R_RETRACT_ZSS;
}
if (user_req & R_DEPLOY_ZSS) {
zss.deploy();
user_req = user_req & ~R_DEPLOY_ZSS;
}
}
void calibrate() {
bool calibrated = false;
int16_t off1, off2, off3;
if (user_req & R_CALIB_GYRO) {
if (imu.calibrateGyroBias()) {
indicator.beepstring((uint8_t) 0b11101110);
imu.get_gyro_offsets(off1, off2, off3);
parameters.gx_off = off1;
parameters.gy_off = off2;
parameters.gz_off = off3;
calibrated = true;
} else {
indicator.beepstring((uint8_t) 0b10001000);
}
user_req = user_req & ~R_CALIB_GYRO;
}
if (user_req & R_CALIB_ACCEL) {
if (imu.calibrateAccelBias(0, 0, GRAV)) {
indicator.beepstring((uint8_t) 0b10101010);
imu.get_accel_offsets(off1, off2, off3);
parameters.ax_off = off1;
parameters.ay_off = off2;