Skip to content

Commit

Permalink
remove mcp23017 library
Browse files Browse the repository at this point in the history
  • Loading branch information
SK21 committed Dec 9, 2024
1 parent 61507d1 commit 3741da8
Show file tree
Hide file tree
Showing 13 changed files with 2,690 additions and 3,047 deletions.
6 changes: 3 additions & 3 deletions Modules/ESP32 Rate/RC_ESP32/RC_ESP32.vcxproj

Large diffs are not rendered by default.

16 changes: 8 additions & 8 deletions Modules/ESP32 Rate/RC_ESP32/Relays.ino
Original file line number Diff line number Diff line change
Expand Up @@ -132,16 +132,16 @@ void CheckRelays()
uint8_t mcpOutB = 0; // Output for port B

// Calculate output for port A, DRV sections 9-16
mcpOutA = (bitRead(RelayLo, 4) ? 2 : 1) |
(bitRead(RelayLo, 5) ? 8 : 4) |
(bitRead(RelayLo, 6) ? 32 : 16) |
(bitRead(RelayLo, 7) ? 128 : 64);
mcpOutA = (bitRead(NewLo, 4) ? 2 : 1) |
(bitRead(NewLo, 5) ? 8 : 4) |
(bitRead(NewLo, 6) ? 32 : 16) |
(bitRead(NewLo, 7) ? 128 : 64);

// Calculate output for port B, DRV sections 1-8
mcpOutB = (bitRead(RelayLo, 0) ? 2 : 1) |
(bitRead(RelayLo, 1) ? 8 : 4) |
(bitRead(RelayLo, 2) ? 32 : 16) |
(bitRead(RelayLo, 3) ? 128 : 64);
mcpOutB = (bitRead(NewLo, 0) ? 2 : 1) |
(bitRead(NewLo, 1) ? 8 : 4) |
(bitRead(NewLo, 2) ? 32 : 16) |
(bitRead(NewLo, 3) ? 128 : 64);

if (MDL.InvertRelay)
{
Expand Down
2,760 changes: 1,282 additions & 1,478 deletions Modules/Nano/NanoRateNB.ino.hex

Large diffs are not rendered by default.

2,760 changes: 1,282 additions & 1,478 deletions Modules/Nano/NanoRateOB.ino.hex

Large diffs are not rendered by default.

25 changes: 18 additions & 7 deletions Modules/Nano/RCnano/Begin.ino
Original file line number Diff line number Diff line change
Expand Up @@ -152,7 +152,7 @@ void DoSetup()
while (!MCP23017_found)
{
Serial.print(".");
Wire.beginTransmission(0x20);
Wire.beginTransmission(MCP23017address);
MCP23017_found = (Wire.endTransmission() == 0);
ErrorCount++;
delay(500);
Expand All @@ -162,13 +162,17 @@ void DoSetup()
Serial.println("");
if (MCP23017_found)
{
Serial.println("MCP23017 found.");
MCP.begin_I2C();
Wire.beginTransmission(MCP23017address);
Wire.write(0x00); // IODIRA register
Wire.write(0x00); // set all of port A to outputs
Wire.endTransmission();

for (int i = 0; i < 16; i++)
{
MCP.pinMode(MDL.RelayPins[i], OUTPUT);
}
Wire.beginTransmission(MCP23017address);
Wire.write(0x01); // IODIRB register
Wire.write(0x00); // set all of port B to outputs
Wire.endTransmission();

Serial.println("MCP23017 found.");
}
else
{
Expand Down Expand Up @@ -231,6 +235,7 @@ void LoadDefaults()
Serial.println("Loading default settings.");

MDL.WorkPin = NC;
MDL.PressurePin = NC;

// default flow pins
Sensor[0].FlowPin = 3;
Expand Down Expand Up @@ -260,6 +265,12 @@ void LoadDefaults()
{
MDL.RelayPins[i] = NC;
}
MDL.SensorCount = 1;
MDL.RelayControl = 2;
MDL.Is3Wire = true;
MDL.ADS1115Enabled = false;
MDL.InvertFlow = false;
MDL.InvertRelay = false;
}

bool ValidData()
Expand Down
14 changes: 7 additions & 7 deletions Modules/Nano/RCnano/Motor.ino
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,13 @@ void AdjustFlow()
if (Sensor[i].PWM >= 0)
{
//increase
digitalWrite(Sensor[i].DirPin, MDL.FlowOnDirection);
digitalWrite(Sensor[i].DirPin, MDL.InvertFlow);
analogWrite(Sensor[i].PWMPin, Sensor[i].PWM);
}
else
{
//decrease
digitalWrite(Sensor[i].DirPin, !MDL.FlowOnDirection);
digitalWrite(Sensor[i].DirPin, !MDL.InvertFlow);
analogWrite(Sensor[i].PWMPin, -Sensor[i].PWM); // offsets the negative pwm value
}
break;
Expand All @@ -27,20 +27,20 @@ void AdjustFlow()
{
if (Sensor[i].PWM >= 0)
{
digitalWrite(Sensor[i].DirPin, MDL.FlowOnDirection);
digitalWrite(Sensor[i].DirPin, MDL.InvertFlow);
analogWrite(Sensor[i].PWMPin, Sensor[i].PWM);
}
else
{
//decrease
digitalWrite(Sensor[i].DirPin, !MDL.FlowOnDirection);
digitalWrite(Sensor[i].DirPin, !MDL.InvertFlow);
analogWrite(Sensor[i].PWMPin, -Sensor[i].PWM); // offsets the negative pwm value
}
}
else
{
// stop flow
digitalWrite(Sensor[i].DirPin, !MDL.FlowOnDirection);
digitalWrite(Sensor[i].DirPin, !MDL.InvertFlow);
analogWrite(Sensor[i].PWMPin, 255);
}
break;
Expand All @@ -53,13 +53,13 @@ void AdjustFlow()
if (Sensor[i].PWM >= 0)
{
//increase
digitalWrite(Sensor[i].DirPin, MDL.FlowOnDirection);
digitalWrite(Sensor[i].DirPin, MDL.InvertFlow);
analogWrite(Sensor[i].PWMPin, Sensor[i].PWM);
}
else
{
//decrease
digitalWrite(Sensor[i].DirPin, !MDL.FlowOnDirection);
digitalWrite(Sensor[i].DirPin, !MDL.InvertFlow);
analogWrite(Sensor[i].PWMPin, -Sensor[i].PWM); // offsets the negative pwm value
}
}
Expand Down
2 changes: 1 addition & 1 deletion Modules/Nano/RCnano/PID.ino
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@

uint32_t LastCheck[MaxProductCount];
const double SampleTime = 50;
const double Deadband = 0.03; // % error below which no adjustment is made
const double Deadband = 0.015; // % error below which no adjustment is made

const double BrakePoint = 0.3; // % error below which reduced adjustment is used
const double BrakeSet = 0.75; // low adjustment rate
Expand Down
77 changes: 41 additions & 36 deletions Modules/Nano/RCnano/RCnano.ino
Original file line number Diff line number Diff line change
@@ -1,41 +1,36 @@
#include <Adafruit_MCP23008.h>
#include <Adafruit_MCP23X08.h>
#include <Adafruit_MCP23X17.h>
#include <Adafruit_MCP23XXX.h>

#include <Wire.h>
#include <EEPROM.h>

#include <Adafruit_BusIO_Register.h>
#include <Adafruit_I2CDevice.h>
#include <Adafruit_I2CRegister.h>
#include <Adafruit_SPIDevice.h>

#include <SPI.h>
#include <EtherCard.h>
#include "PCA95x5_RC.h" // modified from https://github.com/hideakitai/PCA95x5

// rate control with nano
# define InoDescription "RCnano : 25-Nov-2024"
const uint16_t InoID = 25114; // change to send defaults to eeprom, ddmmy, no leading 0
# define InoDescription "RCnano : 8-Dec-2024"
const uint16_t InoID = 8124; // change to send defaults to eeprom, ddmmy, no leading 0
const uint8_t InoType = 2; // 0 - Teensy AutoSteer, 1 - Teensy Rate, 2 - Nano Rate, 3 - Nano SwitchBox, 4 - ESP Rate

#define MaxProductCount 2
#define NC 0xFF // Pins are not connected
const uint8_t MCP23017address = 0x20;

struct ModuleConfig
{
uint8_t ID = 0;
uint8_t SensorCount = 2; // up to 2 sensors, if 0 rate control will be disabled
uint8_t RelayOnSignal = 0; // value that turns on relays
uint8_t FlowOnDirection = 0; // sets on value for flow valve or sets motor direction
uint8_t SensorCount = 1; // up to 2 sensors, if 0 rate control will be disabled
bool InvertRelay = false; // value that turns on relays
bool InvertFlow = false; // sets on value for flow valve or sets motor direction
uint8_t IP0 = 192;
uint8_t IP1 = 168;
uint8_t IP2 = 1;
uint8_t IP3 = 50;
uint8_t RelayControl = 2; // 0 - no relays, 1 - GPIOs, 2 - PCA9555 8 relays, 3 - PCA9555 16 relays, 4 - MCP23017, 5 - PCA9685 single , 6 - PCA9685 paired
uint8_t RelayPins[16] = { 8,9,10,11,12,13,14,15,7,6,5,4,3,2,1,0 }; // MCP23017 pins RC5, RC8
uint8_t RelayControl = 2; // 0 - no relays, 1 - GPIOs, 2 - PCA9555 8 relays, 3 - PCA9555 16 relays, 4 - MCP23017, 5 - PCA9685, 6 - PCF8574
uint8_t WorkPin = NC;
bool WorkPinIsMomentary = false;
bool Is3Wire = true; // False - powered on/off, True - powered on only
uint8_t PressurePin = NC; // NC - no pressure pin
bool ADS1115Enabled = false;
};

ModuleConfig MDL;
Expand Down Expand Up @@ -97,9 +92,6 @@ bool AutoOn = true;
PCA9555 PCA;
bool PCA9555PW_found = false;

Adafruit_MCP23X17 MCP;
bool MCP23017_found = false;

//reset function
void(*resetFunc) (void) = 0;

Expand All @@ -108,6 +100,11 @@ bool WrkOn;
bool WrkLast;
bool WrkCurrent;

int TimedCombo(byte, bool); // function prototype
int16_t CurrentPressure = 0;
bool WorkSwitchOn = false;
bool MCP23017_found = false;

bool EthernetConnected()
{
bool Result = false;
Expand All @@ -119,8 +116,6 @@ bool EthernetConnected()
return Result;
}

int TimedCombo(byte, bool); // function prototype

void setup()
{
DoSetup();
Expand Down Expand Up @@ -155,6 +150,8 @@ void loop()
CheckRelays();
GetUPM();
AdjustFlow();
CheckWorkSwitch();
CheckPressure();
}

SendData();
Expand Down Expand Up @@ -197,7 +194,7 @@ byte CRC(byte Chk[], byte Length, byte Start)
return Result;
}

bool WorkPinOn()
void CheckWorkSwitch()
{
if (MDL.WorkPin < NC)
{
Expand All @@ -206,20 +203,28 @@ bool WorkPinOn()
{
if (WrkCurrent != WrkLast)
{
if (WrkCurrent) WrkOn = !WrkOn; // only cycle when going from low to high
if (WrkCurrent) WorkSwitchOn = !WorkSwitchOn; // only cycle when going from low to high
WrkLast = WrkCurrent;
}
}
else
{
WrkOn = WrkCurrent;
WorkSwitchOn = WrkCurrent;
}
}
else
{
WrkOn = false;
WorkSwitchOn = false;
}
}

void CheckPressure()
{
CurrentPressure = 0;
if (MDL.PressurePin < NC)
{
CurrentPressure = analogRead(MDL.PressurePin) * 10.0;
}
return WrkOn;
}

//uint32_t DebugTime;
Expand All @@ -238,20 +243,20 @@ bool WorkPinOn()
// DebugTime = millis();
// Serial.println("");
//
// //Serial.print(F(" Micros: "));
// //Serial.print(MaxLoopTime);
// Serial.print(F(" Micros: "));
// Serial.print(MaxLoopTime);
//
// //Serial.print(F(", SRAM left: "));
// //Serial.print(MinMem);
// Serial.print(F(", SRAM left: "));
// Serial.print(MinMem);
//
// Serial.print(", ");
// Serial.print(debug1, 7);
// //Serial.print(", ");
// //Serial.print(debug1, 7);
//
// Serial.print(", ");
// Serial.print(debug2, 7);
// //Serial.print(", ");
// //Serial.print(debug2, 7);
//
// Serial.print(", ");
// Serial.print(debug3);
// //Serial.print(", ");
// //Serial.print(debug3);
//
// //Serial.print(", ");
// //Serial.print(MasterSwitchOn);
Expand Down
6 changes: 3 additions & 3 deletions Modules/Nano/RCnano/RCnano.vcxproj

Large diffs are not rendered by default.

9 changes: 6 additions & 3 deletions Modules/Nano/RCnano/Receive.ino
Original file line number Diff line number Diff line change
Expand Up @@ -291,9 +291,11 @@ void ReadPGNs(byte Data[], uint16_t len)
MDL.SensorCount = Data[3];

byte tmp = Data[4];
if ((tmp & 1) == 1) MDL.RelayOnSignal = 1; else MDL.RelayOnSignal = 0;
if ((tmp & 2) == 2) MDL.FlowOnDirection = 1; else MDL.FlowOnDirection = 0;
if ((tmp & 8) == 8) MDL.WorkPinIsMomentary = 1; else MDL.WorkPinIsMomentary = 0;
MDL.InvertRelay = ((tmp & 1) == 1);
MDL.InvertFlow = ((tmp & 2) == 2);
MDL.WorkPinIsMomentary = ((tmp & 8) == 8);
MDL.Is3Wire = ((tmp & 16) == 16);
MDL.ADS1115Enabled = ((tmp & 32) == 32);

MDL.RelayControl = Data[5];
Sensor[0].FlowPin = Data[7];
Expand All @@ -309,6 +311,7 @@ void ReadPGNs(byte Data[], uint16_t len)
}

MDL.WorkPin = Data[29];
MDL.PressurePin = Data[30];

SaveData();

Expand Down
Loading

0 comments on commit 3741da8

Please sign in to comment.