|
1 | 1 | /* |
2 | 2 | sketch for the karaburan motor controller |
3 | | -
|
4 | | -board: Arduino Nano - atmega328(old) |
5 | | -
|
6 | 3 | history: |
7 | 4 | 24-jun-2024 : initial version intergating compass and pwm controller with hard-coded mission |
8 | 5 | 03-jul-2024 : add API via serial i/f |
| 6 | +02-nov-2024 : change outputs to drive LED on a second HW (dummy boat with LEDs instead of motors) |
9 | 7 | */ |
10 | 8 |
|
11 | | -//compass sensor QMC5883L |
| 9 | +//board Arduino Nano |
| 10 | +//sensor |
| 11 | +//QMC5883L |
12 | 12 | /* |
13 | 13 | QMC5883L -> Arduino Nano |
14 | 14 | =========================== |
@@ -57,10 +57,10 @@ GET WD |
57 | 57 | #include <Wire.h> // required? |
58 | 58 |
|
59 | 59 | // Define motor control pins |
60 | | -const int motorAPin1 = 9; // Timer1 output A |
61 | | -const int motorAPin2 = 10; // Timer1 output B |
62 | | -const int motorBPin1 = 3; //timer output? |
63 | | -const int motorBPin2 = 11; //timer output? |
| 60 | +const int motorAPin1 = 9;//green led//pin 9 on boat; // Timer1 output A |
| 61 | +const int motorAPin2 = 10;//red led//pin 10 on boat; // Timer1 output B |
| 62 | +const int motorBPin1 = 3;//led//pin 3 on boat; |
| 63 | +const int motorBPin2 = 11;//led//pin 11 on boat; |
64 | 64 | const int relayPin = 17; |
65 | 65 |
|
66 | 66 | // Define compass DRDY pin |
@@ -162,6 +162,8 @@ void setup() { |
162 | 162 | // Initialize DRDY pin and interrupt |
163 | 163 | //pinMode(drdyPin, INPUT); |
164 | 164 | //attachInterrupt(digitalPinToInterrupt(drdyPin), dataReadyISR, RISING); |
| 165 | + motor_enable=true; |
| 166 | + digitalWrite(relayPin, LOW); |
165 | 167 | Serial.print("Karaburan_motor_drive v0.001 \n OK"); |
166 | 168 | } |
167 | 169 |
|
@@ -415,7 +417,7 @@ void handleWDcommand(String command) { |
415 | 417 | if (timeout == 0) { |
416 | 418 | EndTimeout = 0; |
417 | 419 | Serial.println("OK"); |
418 | | - } else if (timeout>32 or timeout<0){ |
| 420 | + }else if (timeout>32 or timeout<0){ |
419 | 421 | Serial.println("ERR value"); |
420 | 422 | }else{ |
421 | 423 | // Set a timer for the watchdog |
@@ -551,6 +553,32 @@ void loop() { |
551 | 553 | navigateOnCompass(); |
552 | 554 | } |
553 | 555 | } |
| 556 | + |
| 557 | + timeLeft=moveEndTime-currentMillis; |
| 558 | + // Handle move/auto timeout |
| 559 | + if (timeLeft <= 0) { |
| 560 | + nav_state=stop_engine; |
| 561 | + auto_nav = false; |
| 562 | + moveEndTime = 0; |
| 563 | + timeLeft = 0; |
| 564 | + //Serial.println(" time left = 0 "); |
| 565 | + } |
| 566 | + /* |
| 567 | + //motor_enable=true; |
| 568 | + if (EndTimeout == 0 || currentMillis > EndTimeout) { |
| 569 | + //switch relays to boat |
| 570 | + if (motor_enable==true){// to inform timeout only once |
| 571 | + motor_enable=false; |
| 572 | + nav_state=stop_engine;//reset PWMs |
| 573 | + digitalWrite(relayPin, HIGH); |
| 574 | + Serial.println("ERROR {WD:TIMEOUT}"); |
| 575 | + } |
| 576 | + }else{ |
| 577 | + motor_enable=true; |
| 578 | + digitalWrite(relayPin, LOW); |
| 579 | + } |
| 580 | + */ |
| 581 | + |
554 | 582 | if (Serial.available() > 0) { |
555 | 583 | String command = Serial.readStringUntil('\n'); // Read the incoming command |
556 | 584 |
|
@@ -581,30 +609,6 @@ void loop() { |
581 | 609 | } |
582 | 610 | } |
583 | 611 |
|
584 | | - timeLeft=moveEndTime-currentMillis; |
585 | | - // Handle move/auto timeout |
586 | | - if (timeLeft <= 0) { |
587 | | - nav_state=stop_engine; |
588 | | - auto_nav = false; |
589 | | - moveEndTime = 0; |
590 | | - timeLeft = 0; |
591 | | - //Serial.println(" time left = 0 "); |
592 | | - } |
593 | | - //motor_enable=true; |
594 | | - if (EndTimeout == 0 || currentMillis > EndTimeout) { |
595 | | - //switch relays to boat |
596 | | - if (motor_enable==true){// to inform timeout only once |
597 | | - motor_enable=false; |
598 | | - nav_state=stop_engine;//reset PWMs |
599 | | - digitalWrite(relayPin, HIGH); |
600 | | - Serial.println("ERROR {WD:TIMEOUT}"); |
601 | | - } |
602 | | - }else{ |
603 | | - motor_enable=true; |
604 | | - digitalWrite(relayPin, LOW); |
605 | | - } |
606 | | - |
607 | | - |
608 | 612 | // test directiosn |
609 | 613 | /* |
610 | 614 | counter+=1; |
|
0 commit comments