-
Notifications
You must be signed in to change notification settings - Fork 0
/
main.cpp
641 lines (589 loc) · 24.3 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
#include <Arduino.h>
#include <SPI.h>
#include <LoRa.h>
#include <Adafruit_SSD1306.h>
// LoRa Pin Definitions
#define CS_PIN 18
#define IRQ_PIN 26
#define RST_PIN 14
#define SCK_PIN 5
#define MISO 19
#define MOSI 27
// LoRa frequency and sync word
#define LORA_FREQUENCY 915E6
#define LORA_SYNC_WORD 0x15
bool safety_flag_LoRaRx = false; // safety_flag_cmd_vel
unsigned long currentMillis = millis();
unsigned long previousHzCount = 0;
const long intervalHzCount = 5000;
float validatedMsgsHz = 0.0;
int validatedMsgsQty = 0;
int accumulatedRSSI = 0;
int messageCount = 0;
#define SEND_STATE 0
#define RECEIVE_STATE 1
unsigned long stateSwitchInterval = 200; // time in milliseconds to switch state
unsigned long lastStateSwitch = 0; // last time the state was switched
byte state = RECEIVE_STATE; // start in receive state
int messageType;
float msgTypeTwo;
int incomingMsgCount = 0;
int packetSize;
int loopCount = 0;
int gps_status = 0;
float gpsStatusAge = 0;
// cmd_vel variables
float linear_x, angular_z;
bool safety_flag_cmd_vel = false;
unsigned long prev_time_cmdvel = 0;
unsigned long age_of_cmd_vel = 0;
// Data structure definition ////////////////////////////////////
struct RadioControlStruct {
float steering_val;
float throttle_val;
float voltage;
byte estop;
byte control_mode;
unsigned long counter;
} RadioControlData;
struct TractorDataStruct{
float speed;
float heading;
float voltage;
int8_t gps_rtk_status;
unsigned long counter;
} TractorData;
/////////////////////// pins for inputs/outputs///////////////////////
int transmissionPowerPin = 22;
int estopRelay_pin = 23;
int transmissionSignalPin = 17;
int mode_pin = 39; // top on the expansion board
int throttle_pot_pin = 36; // second on the expansion board
int steering_pot_pin = 37; // third on the expansion board
int steer_angle_pin = 38; // pin for steer angle sensor - top on the expansion board
int PWMPin = 25;
int DIRPin = 12;
/////////////////////OLED variables///////////////////////
// OLED definitions
#define OLED_SDA 4
#define OLED_SCL 15
#define OLED_RST 16
#define SCREEN_WIDTH 128 // OLED display width, in pixels
#define SCREEN_HEIGHT 64 // OLED display height, in pixels
Adafruit_SSD1306 display(SCREEN_WIDTH, SCREEN_HEIGHT, &Wire, OLED_RST);
#define row_1 0
#define row_2 9
#define row_3 18
#define row_4 27
#define row_5 36
#define row_6 45
#define row_7 54
unsigned long prev_time_OLED = 0;
////////////////////////////////////////////////////////////////
// timing variables
unsigned long lastPrintMillis = 0;
unsigned long lastDataMillis = 0;
unsigned long prev_time_steer = 0;
const long steerInterval = 100;
unsigned long prev_time_tansmission_control = 0;
const long transmissionInterval = 200;
const long cmd_velInterval = 1500;
unsigned long lastLoraRxTime = 0;
unsigned long ageLoraRx = 0;
const long minlastLoraRx = 3000;
const unsigned long receiveTimeout = 250; // timeout in milliseconds
unsigned long lastPacketReceivedTime = 0;
//steering variables
int steer_effort = 0;
float steer_effort_float = 0;
float steering_actual_angle = 0;
int steering_actual_pot = 0;
float steerSetPoint;
float steer_kp = 0.1;
float steer_ki = 0.1;
float steer_kd = 0.1;
float gain = 0.1; // filter gain
int filtered_steer_pot_int = 0;
float filtered_steering_pot_float = 0.0; // current filtered angle
float prev_angle = 0; // previous filtered angle
//float safety_margin_pot = 10; // reduce this once I complete field testing
//float left_limit_pot = 3470 - safety_margin_pot; // the actual extreme limit is 3400
float left_limit_pot = 3158;
float left_limit_angle = 0.96; // most neg value for cmd_vel.ang.z from 2D Nav goal issued
//float right_limit_pot = 758 + safety_margin_pot; // the actual extreme limit is 520
float right_limit_pot = 798;
float right_limit_angle = -0.96; // // most pos value for cmd_vel.ang.z from 2D Nav goal issued
float tolerance = 0.009; // 1% of 0.96
const int motor_power_limit = 150;
int prevRadioCounter = 0;
int qtyRadioRx = 0;
// steering PID variables
float elapsedTime;
float steerPidError;
unsigned long currentSteerPidTime, previousSteerPidTime;
float lastPidError;
// transmission control variables
#define PWM_RESOLUTION 12
#define PWM_CHANNEL 0
#define PWM_FREQ 50
int tranmissionLogicflag = 0;
float cumSteerPidError, rateError;
float actualSpeed;
int transmissionFullReversePos = 250;
int transmission075ReversePos = 258;
//int transmissionFirstReversePos = ??;
int transmissionNeutralPos = 266;
//int transmissionFirstForwardPos = 303;
int transmission025ForwardPos = 305;
int transmission050ForwardPos = 312;
int transmission075ForwardPos = 315; // 1.0 m/s
int transmissionFullForwardPos = 330; // 1.8 m/s
int transmissionServoValue = transmissionNeutralPos; // neutral position
float left_speed, right_speed;
// variables for parameter settings
const int NUM_SPEED_PARAMS = 8;
int speed_params_array[NUM_SPEED_PARAMS] = {
transmissionFullReversePos,
transmission075ReversePos,
transmissionNeutralPos,
transmission025ForwardPos,
transmission050ForwardPos,
transmission075ForwardPos,
transmissionFullForwardPos,
0,
};
// definitions for USB to TTL UART converter to provide a second Serial connection
#define RX_PIN 21
#define TX_PIN 13
HardwareSerial USB2TTLSerial(2);
int dummyPlaceholder = 0;
/////////////////////// end of declarations //////////////////////////////////
void calcQtyValidatedMsgs(){ // calculate the qty of validated messages and save the results as frequency (i.e. Hz)
if (currentMillis - previousHzCount >= intervalHzCount) {
validatedMsgsHz = validatedMsgsQty / (intervalHzCount/1000);
validatedMsgsQty = 0; // reset the counter every 5 seconds
previousHzCount = currentMillis;
}
}
void getTractorData() {
if (currentMillis - lastDataMillis >= 500) { // 1/2 second
TractorData.speed = actualSpeed;
TractorData.heading = 999.0; // replace with actual data
TractorData.voltage = 999.0; // replace with actual data
TractorData.gps_rtk_status = gps_status;
lastDataMillis = millis();
}
}
void InitLoRa() {
SPI.begin(SCK_PIN, MISO, MOSI, CS_PIN);
LoRa.setPins(CS_PIN, RST_PIN, IRQ_PIN);
if (!LoRa.begin(LORA_FREQUENCY)) {
Serial.println("LoRa initialization failed. Check your connections!");
while (1);
} else {
Serial.println("LoRa initialization successful");
}
LoRa.enableCrc();
LoRa.setSyncWord(LORA_SYNC_WORD);
}
void initializeOLED(){
// Serial.println("In initializeOLED");
pinMode(OLED_RST, OUTPUT);
digitalWrite(OLED_RST, LOW);
delay(20);
digitalWrite(OLED_RST, HIGH);
Wire.begin(OLED_SDA, OLED_SCL);
if (!display.begin(SSD1306_SWITCHCAPVCC, 0x3c, false, false))
{ // Address 0x3C for 128x32
// Serial.println(F("SSD1306 allocation failed"));
while (1)
delay(1000); // loop forever and don't continue
}
display.clearDisplay();
display.setTextColor(WHITE);
display.setTextSize(1);
display.setCursor(0, 0);
display.print("start OLED");
Serial.println("initializeOLED - exit");
}
void displayOLED(){
if (currentMillis - prev_time_OLED >= 1000) { // 1 second
display.clearDisplay();
display.setTextSize(1);
display.setCursor(0, row_1);
display.print("Tractor Cntrl 072623");
// display.setCursor(0,row_2); display.print("RC Volt2:"); display.setCursor(58,row_2); display.print(voltage_val);
display.setCursor(0, row_2); display.print("RSSI:"); display.setCursor(58, row_2); display.println(LoRa.packetRssi());
display.setCursor(0, row_3); display.print("Throttle:"); display.setCursor(58, row_3); display.print(transmissionServoValue);
display.setCursor(0, row_4); display.print("Steering:"); display.setCursor(58, row_4); display.print(abs(steer_effort));
display.setCursor(0, row_5); display.print("P:"); display.setCursor(10, row_5); display.print(steer_kp, 2);
display.setCursor(50, row_5); display.print("I:"); display.setCursor(60, row_5); display.print(steer_ki, 5);
display.setCursor(0, row_6); display.print("D:"); display.setCursor(10, row_6); display.print(steer_kd, 2);
display.setCursor(0, row_7); display.print("Mode SW:"); display.setCursor(58, row_7); display.print(RadioControlData.control_mode);
// display.setCursor(0,57); display.print("T cntr:"); display.setCursor(58,57); display.print(TractorData.counter);
display.display();
// Serial.print(", TractorData.counter: "); Serial.print(TractorData.counter);
prev_time_OLED = millis();
}
}
void TxRxLoRaMsgs(){
//unsigned long currentMillis = millis();
ageLoraRx = currentMillis - lastLoraRxTime;
packetSize = LoRa.parsePacket();
switch (state) {
case SEND_STATE: // transmit LoRa data
TractorData.counter++; // increment the counter each time the function is called
LoRa.beginPacket();
LoRa.write((byte*)&TractorData, sizeof(TractorDataStruct));
LoRa.endPacket();
state = RECEIVE_STATE; // Switch state after sending data
lastPacketReceivedTime = currentMillis; // Reset last packet received time
break;
case RECEIVE_STATE: // receive LoRa data
if (packetSize) {
int rssi = LoRa.packetRssi(); // capture RSSI
accumulatedRSSI += rssi;
messageCount++;
LoRa.readBytes((byte*)&RadioControlData, sizeof(RadioControlStruct));
//String message = "estop received: " + String(RadioControlData.estop);
//Serial.println(message);
validatedMsgsQty++; // increment the count of incoming messages
calcQtyValidatedMsgs(); // calculate the frequency of validated messages
lastLoraRxTime = currentMillis;
//state = SEND_STATE;
lastPacketReceivedTime = currentMillis; // Update last packet received time
} else if (currentMillis - lastPacketReceivedTime >= receiveTimeout) {
state = SEND_STATE; // Switch state after timeout
}
break;
default:
// Handle error or unexpected state
break;
}
}
void printInfoMsg() {
if (currentMillis - lastPrintMillis >= 1000) { // 1 seconds
// average RSSI to include in a print statement
float avgRSSI = 0;
if (messageCount > 0) {
avgRSSI = (float)accumulatedRSSI / messageCount;
}
accumulatedRSSI = 0;
messageCount = 0;
String message = "1, lnr.x: " + String(linear_x, 2)
+ ", ang.z: " + String(angular_z, 2)
+ ", steer_effort: " + String(steer_effort_float, 2)
+ ", steering_actual_angle: " + String(steering_actual_angle, 2)
+ ", steer target: " + String(steerSetPoint, 2);
//Serial.println(message);
message = "2, mode: " + String(RadioControlData.control_mode)
+ ", s_kp " + String(steer_kp, 2)
+ ", s_ki " + String(steer_ki, 6)
+ ", s_kd " + String(steer_kd, 2)
+ ", LoRa sw: " + String(safety_flag_LoRaRx)
+ ", estop sw: " + String(RadioControlData.estop)
+ ", packet size: " + String(packetSize)
+ ", cmd_vel: " + String(safety_flag_cmd_vel);
//Serial.println(message);
qtyRadioRx = RadioControlData.counter - prevRadioCounter;
if (qtyRadioRx > 25){
qtyRadioRx = 25;
}
prevRadioCounter = RadioControlData.counter;
message = "3," + String(tranmissionLogicflag)
+ "," + String(transmissionServoValue)
+ "," + String(filtered_steer_pot_int)
+ "," + String(steering_actual_pot)
+ "," + String(steerSetPoint)
+ "," + String(validatedMsgsHz)
+ "," + String(avgRSSI)
+ "," + String(safety_flag_LoRaRx)
+ "," + String(ageLoraRx)
+ "," + String(gps_status)
+ "," + String(RadioControlData.control_mode)
+ "," + String(steering_actual_angle)
+ "," + String(safety_flag_cmd_vel)
+ "," + String(age_of_cmd_vel)
+ "," + String(qtyRadioRx);
/*
I want to send these data elements via Serial.println in a comma delimeted format:
Transmission logic path being executed (tranmissionLogicflag)
Servo target position (transmissionServoValue)
steering_pot smooth (filtered_steer_pot_int)
steering_pot raw (steering_actual_pot)
Steer angle target (steerSetPoint)
Incoming message rate in Hz (validatedMsgsHz)
Radio signal strength (avgRSSI)
LoRa safety switch (safety_flag_LoRaRx)
Time delta between receiving LoRa messages (ageLoraRx)
gps_rtk_status (gps_status)
mode setting on RC controller(RadioControlData.control_mode)
Current steer angle 0.96 to -0.96 (steering_actual_angle)
*/
Serial.println(message);
/*
Serial.print("Average RSSI: ");
Serial.print(avgRSSI);
Serial.print(" dBm | Rx Hz: ");
Serial.print(validatedMsgsHz);
Serial.print(" loops: ");
Serial.print(loopCount);
Serial.print(" | Tx counter: ");
Serial.print(TractorData.counter);
Serial.print(" | servo min/max: ");
Serial.print(transmissionFullReversePos);
Serial.print(" / ");
Serial.println(transmissionFullForwardPos);
*/
loopCount = 0;
lastPrintMillis = currentMillis; // reset timer
}
}
void getUSB2TTLSerialData(){
if (USB2TTLSerial.available() > 0) {
age_of_cmd_vel = millis() - prev_time_cmdvel;
String incomingData = USB2TTLSerial.readStringUntil('\n');
char incomingDataChar[100];
incomingData.toCharArray(incomingDataChar, 100);
//Serial.println(incomingData);
int commaIndex = incomingData.indexOf(',');
if (commaIndex != -1) {
messageType = incomingData.substring(0, commaIndex).toInt(); // change toInt() for messageType
if (messageType == 1) {
//char incomingDataChar[100];
//incomingData.toCharArray(incomingDataChar, 100);
sscanf(incomingDataChar, "1,%f,%f,%f,%f,%d,%f",
&linear_x,
&angular_z,
&left_speed,
&right_speed,
&gps_status,
&gpsStatusAge);
// Serial.print("gps_status: ");
// Serial.println(gps_status);
prev_time_cmdvel = millis();
incomingMsgCount++; // increment the count of incoming messages
}
else if (messageType == 2) {
/*
int startIndex = commaIndex + 1;
for (int i = 0; i < NUM_SPEED_PARAMS; i++) {
commaIndex = incomingData.indexOf(',', startIndex);
if (commaIndex != -1) {
speed_params_array[i] = incomingData.substring(startIndex, commaIndex).toInt();
startIndex = commaIndex + 1;
} else {
// For the last value, we don't expect another comma so we take the rest of the string.
speed_params_array[i] = incomingData.substring(startIndex).toInt();
break;
}
}
transmissionFullReversePos = speed_params_array[0];
transmission075ReversePos = speed_params_array[1];
transmissionNeutralPos = speed_params_array[2];
transmission025ForwardPos = speed_params_array[3];
transmission050ForwardPos = speed_params_array[4];
transmission075ForwardPos = speed_params_array[5];
transmissionFullForwardPos = speed_params_array[6];
*/
sscanf(incomingDataChar, "2,%d,%d,%d,%d,%d,%d,%d",
&transmissionFullReversePos,
&transmission075ReversePos,
&transmissionNeutralPos,
&transmission025ForwardPos,
&transmission050ForwardPos,
&transmission075ForwardPos,
&transmissionFullForwardPos);
}
}
}
}
float mapfloat(float x, float in_min, float in_max, float out_min, float out_max){
return (x - in_min) * (out_max - out_min) / (in_max - in_min) + out_min;
}
void transmissionPresets(){
tranmissionLogicflag = 10;
if (linear_x >= 1) {
transmissionServoValue = transmissionFullForwardPos;
tranmissionLogicflag = 11;
} else if (linear_x >= 0.75) {
tranmissionLogicflag = 12;
transmissionServoValue = transmission075ForwardPos;
tranmissionLogicflag = 13;
} else if (linear_x >= 0.5) {
tranmissionLogicflag = 14;
transmissionServoValue = transmission050ForwardPos;
} else if (linear_x >= 0.05) {
transmissionServoValue = transmission025ForwardPos;
} else if (linear_x >= -0.05) {
transmissionServoValue = transmissionNeutralPos;
} else if (linear_x >= -0.75) {
transmissionServoValue = transmission075ReversePos;
} else if (linear_x >= -1) {
transmissionServoValue = transmissionFullReversePos;
} else {
transmissionServoValue = transmissionNeutralPos;
tranmissionLogicflag = 15;
}
}
double computeSteeringPID(float inp){
// ref: https://www.teachmemicro.com/arduino-pid-control-tutorial/
currentSteerPidTime = millis(); // get current time
elapsedTime = (double)(currentSteerPidTime - previousSteerPidTime); // compute time elapsed from previous computation
steerPidError = steerSetPoint - inp; // determine error
cumSteerPidError += steerPidError * elapsedTime; // compute integral
rateError = (steerPidError - lastPidError) / elapsedTime; // compute derivative
float out = ((steer_kp * steerPidError) + (steer_ki * cumSteerPidError) + (steer_kd * rateError)); // PID output
lastPidError = steerPidError; // remember current error
previousSteerPidTime = currentSteerPidTime; // remember current time
return out; // have function return the PID output
}
void steerVehicle(){
if ((currentMillis - prev_time_steer) >= steerInterval){
// get the current, actual steering angle
steering_actual_pot = analogRead(steer_angle_pin); // read unfiltered angle
filtered_steering_pot_float = (1 - gain) * prev_angle + gain * steering_actual_pot; // update filtered angle
filtered_steer_pot_int = round(filtered_steering_pot_float);
prev_angle = filtered_steering_pot_float; // store filtered angle for next iteration
steer_kp = 280; //232
steer_ki = 0;
steer_kd = 0;
//steer_kp = mapfloat(analogRead(mode_pin), 0, 4095, 0, 600);
//steer_ki = mapfloat(analogRead(throttle_pot_pin), 0, 4095, 0, 0.0003);
//steer_kd = mapfloat(analogRead(steering_pot_pin), 0, 4095, 0, 2000);
if ((RadioControlData.control_mode == 2) && safety_flag_LoRaRx && safety_flag_cmd_vel) {
steerSetPoint = angular_z; // needs to be changed to ackerman steering angle
} else if ((RadioControlData.control_mode == 1 && safety_flag_LoRaRx)) {
steerSetPoint = RadioControlData.steering_val; // value range needs to match ackerman steering angle range
} else {
steerSetPoint = 0;
}
// steering_actual_pot = analogRead(steer_angle_pin); // now the pot is read in the function that smooths the output
steering_actual_angle = mapfloat(filtered_steer_pot_int, left_limit_pot, right_limit_pot, left_limit_angle, right_limit_angle);
steer_effort_float = computeSteeringPID(steering_actual_angle);
steer_effort = steer_effort_float;
/* Safety clamp: The max_power_limit could be as high as 255 which
would deliver 12+ volts to the steer motor. I have reduced the highest setting that allows the wheels
to be moved easily while sitting on concrete (e.g. motor_power_limit = 150 ) */
if (steer_effort < (motor_power_limit * -1)){
steer_effort = (motor_power_limit * -1);
}
if (steer_effort > motor_power_limit){
steer_effort = motor_power_limit;
}
if (steerPidError > tolerance){
digitalWrite(DIRPin, LOW); // steer right - channel B led is lit; Red wire (+) to motor; positive voltage
// if ((steering_actual_pot > left_limit_pot) || (steering_actual_pot < right_limit_pot)) {steer_effort = 0;} // safety check
analogWrite(PWMPin, steer_effort);
} else if (steerPidError < (tolerance * -1)){
digitalWrite(DIRPin, HIGH); // steer left - channel A led is lit; black wire (-) to motor; negative voltage
// if ((steering_actual_pot > left_limit_pot) || (steering_actual_pot < right_limit_pot)) {steer_effort = 0;} // safety check
analogWrite(PWMPin, abs(steer_effort));
} else {
steer_effort = 0;
// analogWrite(PWMPin, steer_effort); // Turn the motor off
}
prev_time_steer = millis();
}
}
void control_transmission(){
if ((currentMillis - prev_time_tansmission_control) >= transmissionInterval){
tranmissionLogicflag = 0;
actualSpeed = (left_speed + right_speed) / 2.0;
if (RadioControlData.control_mode == 2 && linear_x < 0 && safety_flag_LoRaRx && safety_flag_cmd_vel){
//transmissionServoValue = map(linear_x, -1, 0, transmissionFullReversePos, transmissionNeutralPos);
//transmissionServoValue = constrain(transmissionServoValue, transmissionFullReversePos, transmissionNeutralPos);
transmissionServoValue = transmissionNeutralPos; // until forward motion is working
tranmissionLogicflag = 1;
}
else if (RadioControlData.control_mode == 2 && linear_x >= 0 && safety_flag_LoRaRx && safety_flag_cmd_vel)
{
transmissionPresets();
if (transmissionServoValue > transmissionFullForwardPos) {
transmissionServoValue = transmissionFullForwardPos;
}
if (transmissionServoValue < transmissionNeutralPos) {
transmissionServoValue = transmissionNeutralPos;
}
//tranmissionLogicflag = 2;
}
else if (RadioControlData.control_mode == 1 && safety_flag_LoRaRx) {
transmissionServoValue = map(RadioControlData.throttle_val, 0, 4095, transmissionFullReversePos, transmissionFullForwardPos); // - 60=reverse; 73=neutral; 92=first
tranmissionLogicflag = 3;
} else {
transmissionServoValue = transmissionNeutralPos;
tranmissionLogicflag = 4;
}
digitalWrite(transmissionPowerPin, LOW); // turn power on to transmission servo
ledcWrite(PWM_CHANNEL, transmissionServoValue); // write PWM value to transmission servo
prev_time_tansmission_control = millis();
}
}
void check_cmdvel(){
if (age_of_cmd_vel > cmd_velInterval){
linear_x = 0;
angular_z = 0;
safety_flag_cmd_vel = false;
} else {
safety_flag_cmd_vel = true;
}
}
void eStopRoutine(){
tranmissionLogicflag = 20;
digitalWrite(estopRelay_pin, LOW); // turn the LED on (HIGH is the voltage level)
digitalWrite(transmissionPowerPin, LOW); // make sure power is on to transmission servo
ledcWrite(PWM_CHANNEL, transmissionNeutralPos);
delay(7000);
digitalWrite(transmissionPowerPin, HIGH); // turn power off to transmission servo
String message = "5: e-Stop routine called - relay 2 led should is ON";
Serial.println(message);
RadioControlData.estop = 9;
}
void transmissionServoSetup(){
pinMode(transmissionPowerPin, OUTPUT);
digitalWrite(transmissionPowerPin, LOW); // make sure power is on to transmission servo
ledcSetup(PWM_CHANNEL, PWM_FREQ, PWM_RESOLUTION); // Configure the PWM timer, channel 0, freq 50 Hz and 16 for ESP32 resolution
ledcAttachPin(transmissionSignalPin, PWM_CHANNEL); // Attach the PWM channel to the output pin
}
void check_LoRaRX(){
if (millis() - lastLoraRxTime > minlastLoraRx){
safety_flag_LoRaRx = false;
} else {
safety_flag_LoRaRx = true;
}
}
void setup() {
Serial.begin(115200);
USB2TTLSerial.begin(115200, SERIAL_8N1, RX_PIN, TX_PIN);
delay(10000);
pinMode(steer_angle_pin, INPUT);
pinMode(PWMPin, OUTPUT);
pinMode(DIRPin, OUTPUT);
pinMode(estopRelay_pin, OUTPUT);
transmissionServoSetup();
initializeOLED();
InitLoRa();
RadioControlData.estop = 9;
TractorData.gps_rtk_status = 9;
}
void loop() {
loopCount = loopCount + 1;
currentMillis = millis();
steerVehicle();
control_transmission();
getTractorData();
getUSB2TTLSerialData();
TxRxLoRaMsgs();
//Serial.print("estop: ("); Serial.print(RadioControlData.estop); Serial.println(")");
if (RadioControlData.estop == 0){
eStopRoutine();
} else {
digitalWrite(estopRelay_pin, HIGH);
}
// output info
displayOLED();
printInfoMsg();
// perform safety checks
check_LoRaRX();
check_cmdvel();
}