Skip to content

Commit

Permalink
Merge pull request #16 from tomdebree/master
Browse files Browse the repository at this point in the history
Newer Menu Structure
  • Loading branch information
damienmaguire authored Jan 4, 2019
2 parents 8964184 + 7f172b9 commit 39328fe
Show file tree
Hide file tree
Showing 5 changed files with 1,558 additions and 23 deletions.
136 changes: 113 additions & 23 deletions Gen2TeslaCharger/Gen2TeslaCharger.ino
Original file line number Diff line number Diff line change
@@ -1,3 +1,5 @@


/*
Tesla Gen 2 Charger Control Program
2017-2018
Expand All @@ -14,12 +16,20 @@
#include <DueTimer.h>
#include "config.h"


#define Serial SerialUSB
template<class T> inline Print &operator <<(Print &obj, T arg) {
obj.print(arg);
return obj;
}



int watchdogTime = 1000;




//*********GENERAL VARIABLE DATA ******************
int debugevse = 1; // 1 = show Proximity status and Pilot current limmits
int debug = 1; // 1 = show phase module CAN feedback
Expand All @@ -32,6 +42,9 @@ int state;
unsigned long slavetimeout, tlast, tcan, tboot = 0;
bool bChargerEnabled;


//**************Sleep Variables****************

//*********EVSE VARIABLE DATA ******************
byte Proximity = 0;
uint16_t ACvoltIN = 240; // AC input voltage 240VAC for EU/UK and 110VAC for US
Expand Down Expand Up @@ -81,34 +94,60 @@ int newframe = 0;
ChargerParams parameters;

//*********DCDC Messages VARIABLE DATA ******************
bool dcdcenable = 1; // turn on can messages for the DCDC.
bool dcdcenable = 0; // turn on can messages for the DCDC.

//*********Charger Messages VARIABLE DATA ******************
int ControlID = 0x300;
int StatusID = 0x410;
unsigned long ElconID = 0x18FF50E5;
unsigned long ElconControlID = 0x1806E5F4;

int candebug = 1;

int candebug = 0;

// this function has to be present, otherwise watchdog won't work
void watchdogSetup(void)
{
// do what you want here
}

void setup()
{
pmc_set_writeprotect(false);
pmc_mck_set_prescaler(16);

// 12MHz / 64 * 14 = 2.625MHz // 96 = 110 << 4 = /64
// 12MHz / 32 * 14 = 5.25 MHz // 80 = 101 << 4 = /32
// 12MHz / 16 * 14 = 10.5 MHz // 64 = 100 << 4 = /16
// 12MHz / 8 * 14 = 21 MHz // 48 = 011 << 4 = /8
// 12MHz / 4 * 14 = 42 MHz // 32 = 010 << 4 = /4
// 12MHz / 2 * 14 = 84 MHz // 16 = 001 << 4 = /2 (default)

pmc_disable_periph_clk(22); // TWI/I2C bus 0 (i.MX6 controlling)
pmc_disable_periph_clk(23); // TWI/I2C bus 1
pmc_disable_periph_clk(24); // SPI0
pmc_disable_periph_clk(25); // SPI1
pmc_disable_periph_clk(26); // SSC (I2S digital audio, N/C)

pmc_disable_periph_clk(41); // random number generator
pmc_disable_periph_clk(42); // ethernet MAC - N/C


Serial.begin(115200); //Initialize our USB port which will always be redefined as SerialUSB to use the Native USB port tied directly to the SAM3X processor.

Timer3.attachInterrupt(Charger_msgs).start(90000); // charger messages every 100ms

attachInterrupt(EVSE_PILOT, Pilotread , CHANGE);

watchdogEnable(watchdogTime);
Wire.begin();
EEPROM.read(0, parameters);
if (parameters.version != EEPROM_VERSION)
{
parameters.version = EEPROM_VERSION;
parameters.can0Speed = 500000;
parameters.can1Speed = 500000;
parameters.currReq = 0; //max input limit per module 1500 = 1A
parameters.enabledChargers = 123; // enable per phase - 123 is all phases - 3 is just phase 3
parameters.can0Speed = 500000;
parameters.can1Speed = 500000;
parameters.mainsRelay = 48;
parameters.voltSet = 32000; //1 = 0.01V
parameters.autoEnableCharger = 0; //disable auto start, proximity and pilot control
Expand Down Expand Up @@ -175,8 +214,8 @@ void setup()
///////////////////////////////////////////////////////////////////////////////////////

dcaclim = maxaccur;

bChargerEnabled = false; //are we supposed to command the charger to charge?
//
}

void loop()
Expand All @@ -191,8 +230,9 @@ void loop()

if (Can1.available())
{
//Serial.println();
//Serial.print("can 1 data");
Can1.read(incoming);

canextdecode(incoming);
}

Expand All @@ -202,6 +242,27 @@ void loop()

switch (incomingByte)
{
case 'd'://d for display
Serial.println();
Serial.print(" a ");
Serial.println(parameters.autoEnableCharger);
Serial.print(" e ");
Serial.println(parameters.enabledChargers);
Serial.print(" x ");
Serial.println(parameters.canControl);
Serial.print(" t ");
Serial.println(parameters.type);
Serial.print(" p ");
Serial.println(parameters.phaseconfig + 1);
Serial.print(" 0 ");
Serial.println(parameters.can0Speed * 0.001, 0);
Serial.print(" 1 ");
Serial.println(parameters.can1Speed * 0.001, 0);
Serial.print(" v ");
Serial.println(parameters.voltSet * 0.01, 0);
Serial.print(" c ");
Serial.println(parameters.currReq / 1500);
break;
case 'a'://a for auto enable
if (Serial.available() > 0)
{
Expand Down Expand Up @@ -313,6 +374,32 @@ void loop()
}
break;

case '0': //c for current setting in whole numbers
if (Serial.available() > 0)
{
parameters.can0Speed = long(Serial.parseInt() * 1000);
setting = 1;
Serial.println();
Serial.print(parameters.can0Speed);
Serial.print(",");
Can1.begin(parameters.can0Speed);
Serial.print(Can0.getBusSpeed());
}
break;

case '1': //c for current setting in whole numbers
if (Serial.available() > 0)
{
parameters.can1Speed = long(Serial.parseInt() * 1000);
setting = 1;
Serial.println();
Serial.print(parameters.can1Speed);
Serial.print(",");
Can1.begin(parameters.can1Speed);
Serial.print(Can1.getBusSpeed());
}
break;

default:
// if nothing else matches, do the default
// default is optional
Expand Down Expand Up @@ -523,6 +610,7 @@ void loop()
if (tlast < (millis() - 500))
{
tlast = millis();
watchdogReset();
if (debug != 0)
{
Serial.println();
Expand Down Expand Up @@ -564,8 +652,8 @@ void loop()
Serial.print(acvolt[x]);
Serial.print(" AC cur: ");
Serial.print((accur[x] * 0.06666), 2);
Serial.print(" ");
Serial.print(accur[x]);
//Serial.print(" ");
///Serial.print(accur[x], HEX); ///not needed since current fixed
Serial.print(" DC volt: ");
Serial.print(dcvolt[x]);
Serial.print(" DC cur: ");
Expand Down Expand Up @@ -639,15 +727,12 @@ void loop()
//digitalWrite(EVSE_ACTIVATE, HIGH);//pull pilot low to indicate ready - NOT WORKING freezes PWM reading
if (accurlim > 1400) // one amp or more active modules
{
if (parameters.autoEnableCharger == 1)
if (state == 0)
{
if (state == 0)
if (digitalRead(DIG_IN_1) == HIGH)
{
if (digitalRead(DIG_IN_1) == HIGH)
{
state = 2;// initialize modules
tboot = millis();
}
state = 2;// initialize modules
tboot = millis();
}
}
}
Expand Down Expand Up @@ -717,7 +802,7 @@ void candecode(CAN_FRAME & frame)

case 0x207: //phase 2 msg 0x209. phase 3 msg 0x20B
acvolt[0] = frame.data.bytes[1];
accur[0] = (uint16_t((frame.data.bytes[5] & 0x7F) << 2) | uint16_t(frame.data.bytes[6] >> 6)) ;
accur[0] = uint16_t((frame.data.bytes[6] & 0x03) * 256 + frame.data.bytes[5]) >> 1 ;
x = frame.data.bytes[2] & 12;
if (x != 0)
{
Expand Down Expand Up @@ -749,7 +834,7 @@ void candecode(CAN_FRAME & frame)
break;
case 0x209: //phase 2 msg 0x209. phase 3 msg 0x20B
acvolt[1] = frame.data.bytes[1];
accur[1] = (uint16_t((frame.data.bytes[5] & 0x7F) << 2) | uint16_t(frame.data.bytes[6] >> 6)) ;
accur[1] = uint16_t((frame.data.bytes[6] & 0x03) * 256 + frame.data.bytes[5]) >> 1 ;
x = frame.data.bytes[2] & 12;
if (x != 0)
{
Expand Down Expand Up @@ -781,7 +866,7 @@ void candecode(CAN_FRAME & frame)
break;
case 0x20B: //phase 2 msg 0x209. phase 3 msg 0x20B
acvolt[2] = frame.data.bytes[1];
accur[2] = (uint16_t((frame.data.bytes[5] & 0x7F) << 2) | uint16_t(frame.data.bytes[6] >> 6)) ;
accur[2] = uint16_t((frame.data.bytes[6] & 0x03) * 256 + frame.data.bytes[5]) >> 1 ;
x = frame.data.bytes[2] & 12;
if (x != 0)
{
Expand Down Expand Up @@ -944,6 +1029,11 @@ void Charger_msgs()

/////////Elcon Message////////////

outframe.id = ElconID;
if ( parameters.canControl == 3)
{
outframe.id = ElconID + 1;
}
outframe.id = ElconID;
outframe.length = 8; // Data payload 8 bytes
outframe.extended = 1; // Extended addresses - 0=11-bit 1=29bit
Expand Down Expand Up @@ -1128,7 +1218,7 @@ void ACcurrentlimit()
{
if (modulelimcur > (dcaclim * 1.5)) //if more current then max per module or limited by DC output current
{
modulelimcur = (dcaclim * 1.5);
// modulelimcur = (dcaclim * 1.5);
}
if (modulelimcur > parameters.currReq) //if evse allows more current then set in parameters limit it
{
Expand All @@ -1139,7 +1229,7 @@ void ACcurrentlimit()
{
if (modulelimcur > (dcaclim * 0.5)) //if more current then max per module or limited by DC output current
{
modulelimcur = (dcaclim * 0.5);
//modulelimcur = (dcaclim * 0.5);
}
if (modulelimcur > (parameters.currReq / activemodules)) //if evse allows more current then set in parameters limit it
{
Expand All @@ -1160,14 +1250,14 @@ void DCcurrentlimit()
totdccur = totdccur + (dccur[x] * 0.1678466) ;
}
dcaclim = 0;
int x = 2;
int x = 0;
if (totdccur > 0.2)
{
dcaclim = (((float)dcvolt[x] / (float)acvolt[x]) * (maxdccur * 1.2)) ; /// activemodules
}
else
{
dcaclim = 5000;
dcaclim = 5000;
}
}

Expand Down
Loading

0 comments on commit 39328fe

Please sign in to comment.