Skip to content

Commit

Permalink
fix defaults
Browse files Browse the repository at this point in the history
  • Loading branch information
SK21 committed Dec 15, 2024
1 parent fad4b7a commit 9f2022e
Show file tree
Hide file tree
Showing 5 changed files with 61 additions and 62 deletions.
Binary file modified Modules/ESP32 Rate/RC_ESP32.ino.bin
Binary file not shown.
20 changes: 10 additions & 10 deletions Modules/ESP32 Rate/RC_ESP32/Begin.ino
Original file line number Diff line number Diff line change
Expand Up @@ -390,18 +390,18 @@ void LoadDefaults()
{
Serial.println("Loading default settings.");

// RC17
MDL.WorkPin = 13;
MDL.PressurePin = 33;
// RC15
MDL.WorkPin = NC;
MDL.PressurePin = NC;

// default flow pins
Sensor[0].FlowPin = 32;
Sensor[0].IN1 = 4;
Sensor[0].IN2 = 16;
Sensor[0].FlowPin = 17;
Sensor[0].IN1 = 32;
Sensor[0].IN2 = 33;

Sensor[1].FlowPin = NC;
Sensor[1].IN1 = NC;
Sensor[1].IN2 = NC;
Sensor[1].FlowPin = 16;
Sensor[1].IN1 = 25;
Sensor[1].IN2 = 26;

// default pid
Sensor[0].KP = 5;
Expand All @@ -422,7 +422,7 @@ void LoadDefaults()
MDL.RelayPins[i] = NC;
}
MDL.SensorCount = 1;
MDL.RelayControl = 4;
MDL.RelayControl = 5;
MDL.WifiModeUseStation = false;
MDL.Is3Wire = true;
MDL.ADS1115Enabled = false;
Expand Down
96 changes: 48 additions & 48 deletions Modules/ESP32 Rate/RC_ESP32/RC_ESP32.ino
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@
#include <EthernetUdp.h>

// rate control with ESP32 board: DOIT ESP32 DEVKIT V1
# define InoDescription "RC_ESP32 : 03-Dec-2024"
const uint16_t InoID = 3124; // change to send defaults to eeprom, ddmmy, no leading 0
# define InoDescription "RC_ESP32 : 14-Dec-2024"
const uint16_t InoID = 14124; // change to send defaults to eeprom, ddmmy, no leading 0
const uint8_t InoType = 4; // 0 - Teensy AutoSteer, 1 - Teensy Rate, 2 - Nano Rate, 3 - Nano SwitchBox, 4 - ESP Rate
const uint8_t Processor = 0; // 0 - ESP32-Wroom-32U

Expand Down Expand Up @@ -220,7 +220,7 @@ void loop()
}
SendComm();
server.handleClient();
Blink();
//Blink();
}

byte ParseModID(byte ID)
Expand Down Expand Up @@ -296,48 +296,48 @@ void CheckPressure()
}
}

bool State = false;
uint32_t LastBlink;
uint32_t LastLoop;
byte ReadReset;
uint32_t MaxLoopTime;
double debug1;
double debug2;
double debug3;
double debug4;

void Blink()
{
if (millis() - LastBlink > 1000)
{
LastBlink = millis();
State = !State;
//digitalWrite(LED_BUILTIN, State);

//Serial.print(" Micros: ");
//Serial.print(MaxLoopTime);
debug1 = Sensor[0].FlowPin;
debug2 = Sensor[0].MeterCal;
//Serial.print(", ");
Serial.print(debug1);

Serial.print(", ");
Serial.print(debug2);

Serial.print(", ");
Serial.print(debug3);

Serial.print(", ");
Serial.print(debug4);

Serial.println("");

if (ReadReset++ > 5)
{
ReadReset = 0;
MaxLoopTime = 0;
}
}
if (micros() - LastLoop > MaxLoopTime) MaxLoopTime = micros() - LastLoop;
LastLoop = micros();
}
//bool State = false;
//uint32_t LastBlink;
//uint32_t LastLoop;
//byte ReadReset;
//uint32_t MaxLoopTime;
//double debug1;
//double debug2;
//double debug3;
//double debug4;
//
//void Blink()
//{
// if (millis() - LastBlink > 1000)
// {
// LastBlink = millis();
// State = !State;
// //digitalWrite(LED_BUILTIN, State);
//
// //Serial.print(" Micros: ");
// //Serial.print(MaxLoopTime);
// debug1 = Sensor[0].FlowPin;
// debug2 = Sensor[0].MeterCal;
// //Serial.print(", ");
// Serial.print(debug1);
//
// Serial.print(", ");
// Serial.print(debug2);
//
// Serial.print(", ");
// Serial.print(debug3);
//
// Serial.print(", ");
// Serial.print(debug4);
//
// Serial.println("");
//
// if (ReadReset++ > 5)
// {
// ReadReset = 0;
// MaxLoopTime = 0;
// }
// }
// if (micros() - LastLoop > MaxLoopTime) MaxLoopTime = micros() - LastLoop;
// LastLoop = micros();
//}
6 changes: 3 additions & 3 deletions Modules/ESP32 Rate/RC_ESP32/RC_ESP32.vcxproj

Large diffs are not rendered by default.

1 change: 0 additions & 1 deletion Modules/ESP32 Rate/RC_ESP32/Rate.ino
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,6 @@ void GetUPM()
{
if (PulseCount[i] && Sensor[i].MeterCal > 0)
{
debug3++;
LastPulse[i] = millis();

noInterrupts();
Expand Down

0 comments on commit 9f2022e

Please sign in to comment.