Skip to content

Commit 7458d91

Browse files
authored
Update boat_vehicle.ino (disable watchdog)
commented out watchdog check, actually handled with timeLeft variable for moving commandos (MOVE, NAV). PWM commandos is not time limited.
1 parent 8723d80 commit 7458d91

File tree

1 file changed

+37
-33
lines changed

1 file changed

+37
-33
lines changed

motor_controller/boat_vehicle.ino

Lines changed: 37 additions & 33 deletions
Original file line numberDiff line numberDiff line change
@@ -1,14 +1,14 @@
11
/*
22
sketch for the karaburan motor controller
3-
4-
board: Arduino Nano - atmega328(old)
5-
63
history:
74
24-jun-2024 : initial version intergating compass and pwm controller with hard-coded mission
85
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)
97
*/
108

11-
//compass sensor QMC5883L
9+
//board Arduino Nano
10+
//sensor
11+
//QMC5883L
1212
/*
1313
QMC5883L -> Arduino Nano
1414
===========================
@@ -57,10 +57,10 @@ GET WD
5757
#include <Wire.h> // required?
5858

5959
// 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;
6464
const int relayPin = 17;
6565

6666
// Define compass DRDY pin
@@ -162,6 +162,8 @@ void setup() {
162162
// Initialize DRDY pin and interrupt
163163
//pinMode(drdyPin, INPUT);
164164
//attachInterrupt(digitalPinToInterrupt(drdyPin), dataReadyISR, RISING);
165+
motor_enable=true;
166+
digitalWrite(relayPin, LOW);
165167
Serial.print("Karaburan_motor_drive v0.001 \n OK");
166168
}
167169

@@ -415,7 +417,7 @@ void handleWDcommand(String command) {
415417
if (timeout == 0) {
416418
EndTimeout = 0;
417419
Serial.println("OK");
418-
} else if (timeout>32 or timeout<0){
420+
}else if (timeout>32 or timeout<0){
419421
Serial.println("ERR value");
420422
}else{
421423
// Set a timer for the watchdog
@@ -551,6 +553,32 @@ void loop() {
551553
navigateOnCompass();
552554
}
553555
}
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+
554582
if (Serial.available() > 0) {
555583
String command = Serial.readStringUntil('\n'); // Read the incoming command
556584

@@ -581,30 +609,6 @@ void loop() {
581609
}
582610
}
583611

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-
608612
// test directiosn
609613
/*
610614
counter+=1;

0 commit comments

Comments
 (0)