diff --git a/BatteryManager.cpp b/BatteryManager.cpp index 7894f34..95eb470 100644 --- a/BatteryManager.cpp +++ b/BatteryManager.cpp @@ -70,3 +70,5 @@ signed int BatteryManager::getPackCurrent() return packCurrent; } + + diff --git a/BatteryManager.h b/BatteryManager.h index ec97268..bf1d761 100644 --- a/BatteryManager.h +++ b/BatteryManager.h @@ -66,3 +66,5 @@ class BatteryManager : public Device { }; #endif + + diff --git a/BrusaMotorController.cpp b/BrusaMotorController.cpp index f2b3b75..1c278c2 100644 --- a/BrusaMotorController.cpp +++ b/BrusaMotorController.cpp @@ -376,3 +376,5 @@ void BrusaMotorController::saveConfiguration() { // prefsHandler->write(EEMC_, config->enableOscillationLimiter); prefsHandler->saveChecksum(); } + + diff --git a/BrusaMotorController.h b/BrusaMotorController.h index e05b2a9..10a49ca 100644 --- a/BrusaMotorController.h +++ b/BrusaMotorController.h @@ -185,3 +185,5 @@ class BrusaMotorController: public MotorController, CanObserver { }; #endif /* BRUSAMOTORCONTROLLER_H_ */ + + diff --git a/CanBrake.cpp b/CanBrake.cpp index e49fa65..8eeb994 100644 --- a/CanBrake.cpp +++ b/CanBrake.cpp @@ -224,3 +224,5 @@ void CanBrake::saveConfiguration() { prefsHandler->write(EETH_CAR_TYPE, config->carType); prefsHandler->saveChecksum(); } + + diff --git a/CanBrake.h b/CanBrake.h index c4777f5..819c506 100644 --- a/CanBrake.h +++ b/CanBrake.h @@ -69,3 +69,5 @@ class CanBrake: public Throttle, CanObserver { }; #endif /* CAN_BRAKE_H_ */ + + diff --git a/CanHandler.cpp b/CanHandler.cpp index 41162f2..367d45f 100644 --- a/CanHandler.cpp +++ b/CanHandler.cpp @@ -146,14 +146,15 @@ void CanHandler::detach(CanObserver* observer, uint32_t id, uint32_t mask) { * \param frame - the received can frame to log */ void CanHandler::logFrame(CAN_FRAME& frame) { - if (Logger::isDebug()) { - Logger::debug("CAN: dlc=%X fid=%X id=%X ide=%X rtr=%X data=%X,%X,%X,%X,%X,%X,%X,%X", - frame.length, frame.fid, frame.id, frame.extended, frame.rtr, - frame.data.bytes[0], frame.data.bytes[1], frame.data.bytes[2], frame.data.bytes[3], - frame.data.bytes[4], frame.data.bytes[5], frame.data.bytes[6], frame.data.bytes[7]); - } + if (Logger::isDebug()) { + Logger::debug("CAN: dlc=%X fid=%X id=%X ide=%X rtr=%X data=%X,%X,%X,%X,%X,%X,%X,%X", + frame.length, frame.fid, frame.id, frame.extended, frame.rtr, + frame.data.bytes[0], frame.data.bytes[1], frame.data.bytes[2], frame.data.bytes[3], + frame.data.bytes[4], frame.data.bytes[5], frame.data.bytes[6], frame.data.bytes[7]); + } } + /* * Find a observerData entry which is not in use. * @@ -194,7 +195,7 @@ void CanHandler::process() { if (bus->rx_avail()) { bus->get_rx_buff(frame); - logFrame(frame); + //logFrame(frame); for (int i = 0; i < CFG_CAN_NUM_OBSERVERS; i++) { if (observerData[i].observer != NULL) { @@ -202,6 +203,9 @@ void CanHandler::process() { if ((frame.id & observerData[i].mask) == (observerData[i].id & observerData[i].mask)) observerData[i].observer->handleCanFrame(&frame); } + + if(frame.id==CAN_SWITCH)CANIO(frame); + } } } @@ -210,6 +214,7 @@ void CanHandler::process() { //(whatever happens to be open) or queue it to send (if nothing is open) void CanHandler::sendFrame(CAN_FRAME& frame) { bus->sendFrame(frame); + // logFrame(frame); } /* @@ -219,3 +224,54 @@ void CanHandler::sendFrame(CAN_FRAME& frame) { void CanObserver::handleCanFrame(CAN_FRAME *frame) { Logger::error("CanObserver does not implement handleCanFrame(), frame.id=%d", frame->id); } + + +void CanHandler::CANIO(CAN_FRAME& frame) { + + static CAN_FRAME CANioFrame; + + CANioFrame.id = CAN_OUTPUTS; + CANioFrame.length = 8; + CANioFrame.extended = 0; //standard frame + CANioFrame.rtr = 0; + + for(int i=0;i==8;i++) + { + if(frame.data.bytes[i]==0x88)setOutput(i,true); + if(frame.data.bytes[i]==0xFF)setOutput(i,false); + } + + for(int i=0;i==8;i++) + { + if(getOutput(i))CANioFrame.data.bytes[i]=0x88; + else CANioFrame.data.bytes[i]=0xFF; + } + + sendFrame(CANioFrame); + + + CANioFrame.id = CAN_ANALOG_INPUTS; + int i=0; + uint16_t anaVal; + + for(int j=0;j>6;j+=2) + { + anaVal=getAnalog(i++); + CANioFrame.data.bytes[j]=highByte (anaVal); + CANioFrame.data.bytes[j+1]=lowByte(anaVal); + } + + sendFrame(CANioFrame); + + CANioFrame.id = CAN_DIGITAL_INPUTS; + CANioFrame.length = 4; + + for(int i=0;i==4;i++) + { + if (getDigital(i))CANioFrame.data.bytes[i]=0x88; + else CANioFrame.data.bytes[i]=0xff; + } + + sendFrame(CANioFrame); +} + diff --git a/CanHandler.h b/CanHandler.h index d0931a9..b2b8bb4 100644 --- a/CanHandler.h +++ b/CanHandler.h @@ -34,6 +34,7 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. #include #include "Logger.h" #include "DeviceManager.h" +#include "sys_io.h" class Device; @@ -54,6 +55,7 @@ class CanHandler { void detach(CanObserver *observer, uint32_t id, uint32_t mask); void process(); void sendFrame(CAN_FRAME& frame); + void CANIO(CAN_FRAME& frame); static CanHandler *getInstanceCar(); static CanHandler *getInstanceEV(); protected: @@ -80,3 +82,5 @@ class CanHandler { }; #endif /* CAN_HANDLER_H_ */ + + diff --git a/CanPIDListener.cpp b/CanPIDListener.cpp index ec674fb..50957ee 100644 --- a/CanPIDListener.cpp +++ b/CanPIDListener.cpp @@ -332,3 +332,5 @@ void CanPIDListener::saveConfiguration() { //prefsHandler->saveChecksum(); } + + diff --git a/CanPIDListener.h b/CanPIDListener.h index 1b3b81b..3b3f250 100644 --- a/CanPIDListener.h +++ b/CanPIDListener.h @@ -64,4 +64,6 @@ class CanPIDListener: public Device, CanObserver { bool processShowCustomData(CAN_FRAME* inFrame, CAN_FRAME& outFrame); }; -#endif //CAN_PID_H_ \ No newline at end of file +#endif //CAN_PID_H_ + + diff --git a/CanThrottle.cpp b/CanThrottle.cpp index 6545730..9d76808 100644 --- a/CanThrottle.cpp +++ b/CanThrottle.cpp @@ -195,3 +195,5 @@ void CanThrottle::saveConfiguration() { prefsHandler->write(EETH_CAR_TYPE, config->carType); prefsHandler->saveChecksum(); } + + diff --git a/CanThrottle.h b/CanThrottle.h index be98e14..82c7b27 100644 --- a/CanThrottle.h +++ b/CanThrottle.h @@ -73,3 +73,5 @@ class CanThrottle: public Throttle, CanObserver { }; #endif /* CAN_THROTTLE_H_ */ + + diff --git a/CodaMotorController.cpp b/CodaMotorController.cpp index 648da0e..3e77975 100644 --- a/CodaMotorController.cpp +++ b/CodaMotorController.cpp @@ -146,16 +146,21 @@ void CodaMotorController::handleCanFrame(CAN_FRAME *frame) void CodaMotorController::handleTick() { - + MotorController::handleTick(); //kick the ball up to papa sendCmd1(); //Send our lone torque command - if (millis()-mss>2000 && online==0) - { - running=false; // We haven't received any UQM frames for over 2 seconds. Otherwise online would be 1. - mss=millis(); //So we've lost communications. Let's turn off the running light. - faultHandler.raiseFault(CODAUQM, FAULT_MOTORCTRL_COMM, true); - } - online=0;//This flag will be set to 1 by received frames. + + if(!online) //This routine checks to see if we have received any frames from the inverter. If so, ONLINE would be true and + { //we set the RUNNING light on. If no frames are received for 2 seconds, we set running OFF. + if (millis()-mss>2000) + { + running=false; // We haven't received any frames for over 2 seconds. Otherwise online would be true. + mss=millis(); //Reset our 2 second timer + } + } + else running=true; + online=false;//This flag will be set to true by received frames + } @@ -330,3 +335,5 @@ void CodaMotorController::timestamp() // Serial< inline Print &operator <<(Print &obj, T arg) { obj.print(arg); return obj; } + + + +DCDCController::DCDCController() : Device() +{ + prefsHandler = new PrefHandler(DCDC); + //prefsHandler->setEnabledStatus(true); + + commonName = "Delphi DC-DC Converter"; + +} + + + +void DCDCController::handleCanFrame(CAN_FRAME *frame) +{ + Logger::debug("DCDC msg: %X", frame->id); + Logger::debug("DCDC data: %X%X%X%X%X%X%X%X", frame->data.bytes[0],frame->data.bytes[1],frame->data.bytes[2],frame->data.bytes[3],frame->data.bytes[4],frame->data.bytes[5],frame->data.bytes[6],frame->data.bytes[7]); +} + + + +void DCDCController::setup() +{ + TickHandler::getInstance()->detach(this); + + loadConfiguration(); + Device::setup(); // run the parent class version of this function + + CanHandler::getInstanceCar()->attach(this, 0x1D5, 0x7ff, false); + //Watch for 0x1D5 messages from Delphi converter + TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_DCDC); +} + + +void DCDCController::handleTick() { + + Device::handleTick(); //kick the ball up to papa + + sendCmd(); //Send our Delphi voltage control command + +} + + +/* +1D7 08 80 77 00 00 00 00 00 00 +For 13.0 vdc output. + +1D7 08 80 8E 00 00 00 00 00 00 +For 13.5 vdc output. + +To request 14.0 vdc, the message was: +1D7 08 80 A5 00 00 00 00 00 00 +*/ + +void DCDCController::sendCmd() +{ + DCDCConfiguration *config = (DCDCConfiguration *)getConfiguration(); + + CAN_FRAME output; + output.length = 8; + output.id = 0x1D7; + output.extended = 0; //standard frame + output.rtr = 0; + output.fid = 0; + output.data.bytes[0] = 0x80; + output.data.bytes[1] = 0x8E; + output.data.bytes[2] = 0; + output.data.bytes[3] = 0; + output.data.bytes[4] = 0; + output.data.bytes[5] = 0; + output.data.bytes[6] = 0; + output.data.bytes[7] = 0x00; + + CanHandler::getInstanceCar()->sendFrame(output); + timestamp(); + Logger::debug("Delphi DC-DC cmd: %X %X %X %X %X %X %X %X %X %d:%d:%d.%d",output.id, output.data.bytes[0], + output.data.bytes[1],output.data.bytes[2],output.data.bytes[3],output.data.bytes[4],output.data.bytes[5],output.data.bytes[6],output.data.bytes[7], hours, minutes, seconds, milliseconds); +} + +DeviceId DCDCController::getId() { + return (DCDC); +} + +uint32_t DCDCController::getTickInterval() +{ + return CFG_TICK_INTERVAL_DCDC; +} + +void DCDCController::loadConfiguration() { + DCDCConfiguration *config = (DCDCConfiguration *)getConfiguration(); + + if (!config) { + config = new DCDCConfiguration(); + setConfiguration(config); + } + + Device::loadConfiguration(); // call parent +} + +void DCDCController::saveConfiguration() { + Device::saveConfiguration(); +} + +void DCDCController::timestamp() +{ + milliseconds = (int) (millis()/1) %1000 ; + seconds = (int) (millis() / 1000) % 60 ; + minutes = (int) ((millis() / (1000*60)) % 60); + hours = (int) ((millis() / (1000*60*60)) % 24); +} + + diff --git a/DCDCController.h b/DCDCController.h new file mode 100644 index 0000000..53c61bb --- /dev/null +++ b/DCDCController.h @@ -0,0 +1,70 @@ +/* + * DCDCController.h + * + * + * + Copyright (c) 2014 Jack Rickard + + Permission is hereby granted, free of charge, to any person obtaining + a copy of this software and associated documentation files (the + "Software"), to deal in the Software without restriction, including + without limitation the rights to use, copy, modify, merge, publish, + distribute, sublicense, and/or sell copies of the Software, and to + permit persons to whom the Software is furnished to do so, subject to + the following conditions: + + The above copyright notice and this permission notice shall be included + in all copies or substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + */ + +#ifndef DCDC_H_ +#define DCDC_H_ + +#include +#include "config.h" +#include "Device.h" +#include "sys_io.h" +#include "TickHandler.h" +#include "CanHandler.h" + +/* + * Class for Delphi DCDC specific configuration parameters + */ +class DCDCConfiguration : public DeviceConfiguration { +public: +}; + +class DCDCController: public Device, CanObserver { +public: + virtual void handleTick(); + virtual void handleCanFrame(CAN_FRAME *frame); + virtual void setup(); + + DCDCController(); + void timestamp(); + DeviceId getId(); + uint32_t getTickInterval(); + + virtual void loadConfiguration(); + virtual void saveConfiguration(); + +private: + int milliseconds ; + int seconds; + int minutes; + int hours; + void sendCmd(); +}; + +#endif /* DCDC_H_ */ + + diff --git a/Device.cpp b/Device.cpp index 85c0130..abb29d4 100644 --- a/Device.cpp +++ b/Device.cpp @@ -86,3 +86,5 @@ void Device::setConfiguration(DeviceConfiguration *configuration) { this->deviceConfiguration = configuration; } + + diff --git a/Device.h b/Device.h index 3a16922..729d469 100644 --- a/Device.h +++ b/Device.h @@ -73,3 +73,5 @@ class Device: public TickObserver { }; #endif /* DEVICE_H_ */ + + diff --git a/DeviceManager.cpp b/DeviceManager.cpp index ff486a2..d61179b 100644 --- a/DeviceManager.cpp +++ b/DeviceManager.cpp @@ -298,7 +298,7 @@ void DeviceManager::updateWifi() { sendMessage(DEVICE_WIFI, ICHIP2128, MSG_CONFIG_CHANGE, NULL); //Load all our other parameters first - char param [2][20]; //A two element array containing id and enable state + char param [2][30]; //A two element array containing id and enable state char *paramPtr[2] = { ¶m[0][0], ¶m[1][0] }; //A two element array of pointers, pointing to the addresses of row 1 and row 2 of array. //paramPtr[0] then contains address of param row 0 element 0 //paramPtr[1] then contains address of param row 1 element 0. @@ -329,3 +329,5 @@ void DeviceManager::updateWifi() { } + + diff --git a/DeviceManager.h b/DeviceManager.h index 24a9e53..592187f 100644 --- a/DeviceManager.h +++ b/DeviceManager.h @@ -76,3 +76,5 @@ class DeviceManager { }; #endif + + diff --git a/DeviceTypes.h b/DeviceTypes.h index a4cc9e7..b72a103 100644 --- a/DeviceTypes.h +++ b/DeviceTypes.h @@ -45,21 +45,26 @@ enum DeviceId { //unique device ID for every piece of hardware possible BRUSA_DMC5 = 0x1001, CODAUQM = 0x1002, BRUSACHARGE = 0x1010, - TCCHCHARGE = 0x1020, + TCCHCHARGE = 0x1011, + LEAR=0x1012, THROTTLE = 0x1030, POTACCELPEDAL = 0x1031, POTBRAKEPEDAL = 0x1032, CANACCELPEDAL = 0x1033, CANBRAKEPEDAL = 0x1034, + EVICTUS = 0x4400, ICHIP2128 = 0x1040, + DCDC = 0x1050, THINKBMS = 0x2000, FAULTSYS = 0x4000, SYSTEM = 0x5000, HEARTBEAT = 0x5001, MEMCACHE = 0x5002, PIDLISTENER = 0x6000, - ELM327EMU = 0x6500, + ELM327EMU = 0x650, INVALID = 0xFFFF }; #endif /* DEVICE_TYPES_H_ */ + + diff --git a/DmocMotorController.cpp b/DmocMotorController.cpp index b29dead..d83c009 100644 --- a/DmocMotorController.cpp +++ b/DmocMotorController.cpp @@ -91,7 +91,7 @@ void DmocMotorController::setup() { void DmocMotorController::handleCanFrame(CAN_FRAME *frame) { int RotorTemp, invTemp, StatorTemp; int temp; - online = 1; //if a frame got to here then it passed the filter and must have been from the DMOC + online = true; //if a frame got to here then it passed the filter and must have been from the DMOC Logger::debug("DMOC CAN received: %X %X %X %X %X %X %X %X %X", frame->id,frame->data.bytes[0] ,frame->data.bytes[1],frame->data.bytes[2],frame->data.bytes[3],frame->data.bytes[4],frame->data.bytes[5],frame->data.bytes[6],frame->data.bytes[70]); @@ -203,14 +203,19 @@ void DmocMotorController::handleTick() { setSelectedGear(NEUTRAL); //We will stay in NEUTRAL until we get at least 40 frames ahead indicating continous communications. } - if (millis()-ms>2000 && online==0) - { - running=false; // We haven't received any frames for over 2 seconds. Otherwise online would be 1. - ms=millis(); //So we've lost communications. Let's turn off the running light. - } - running=online; - online=0;//This flag will be set to 1 by received frames. - + + if(!online) //This routine checks to see if we have received any frames from the inverter. If so, ONLINE would be true and + { //we set the RUNNING light on. If no frames are received for 2 seconds, we set running OFF. + if ((millis()-ms)>2000) + { + running=false; // We haven't received any frames for over 2 seconds. Otherwise online would be true. + ms=millis(); //Reset our 2 second timer + } + } + else running=true; + online=false;//This flag will be set to 1 by received frames. + + sendCmd1(); //This actually sets our GEAR and our actualstate cycle sendCmd2(); //This is our torque command sendCmd3(); @@ -440,3 +445,5 @@ void DmocMotorController::timestamp() } + + diff --git a/DmocMotorController.h b/DmocMotorController.h old mode 100755 new mode 100644 index dcce79d..d42a8a5 --- a/DmocMotorController.h +++ b/DmocMotorController.h @@ -94,3 +94,5 @@ class DmocMotorController: public MotorController, CanObserver { #endif /* DMOC_H_ */ + + diff --git a/ELM327Processor.cpp b/ELM327Processor.cpp index 5185147..249a890 100644 --- a/ELM327Processor.cpp +++ b/ELM327Processor.cpp @@ -108,3 +108,5 @@ String ELM327Processor::processELMCmd(char *cmd) { return retString; } + + diff --git a/ELM327Processor.h b/ELM327Processor.h index 2195e17..cbc4110 100644 --- a/ELM327Processor.h +++ b/ELM327Processor.h @@ -19,4 +19,6 @@ class ELM327Processor { bool bHeader; }; -#endif \ No newline at end of file +#endif + + diff --git a/ELM327_Emu.cpp b/ELM327_Emu.cpp index a1c15c1..0c45352 100644 --- a/ELM327_Emu.cpp +++ b/ELM327_Emu.cpp @@ -183,4 +183,6 @@ void ELM327Emu::saveConfiguration() { // prefsHandler->write(EESYS_WIFI0_SSID, config->ssid); // prefsHandler->saveChecksum(); } - \ No newline at end of file + + + diff --git a/ELM327_Emu.h b/ELM327_Emu.h index b868f9c..8395a29 100644 --- a/ELM327_Emu.h +++ b/ELM327_Emu.h @@ -33,7 +33,7 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. /* List of AT commands to support: AT E0 (turn echo off) -AT H (0/1) - Turn headers on or off - headers are used to determine how many ECU’s present (hint: only send one response to 0100 and emulate a single ECU system to save time coding) +AT H (0/1) - Turn headers on or off - headers are used to determine how many ECUís present (hint: only send one response to 0100 and emulate a single ECU system to save time coding) AT L0 (Turn linefeeds off - just use CR) AT Z (reset) AT SH - Set header address - seems to set the ECU address to send to (though you may be able to ignore this if you wish) @@ -96,3 +96,5 @@ class ELM327Emu : public Device { }; #endif + + diff --git a/EVIC.cpp b/EVIC.cpp new file mode 100644 index 0000000..805e3eb --- /dev/null +++ b/EVIC.cpp @@ -0,0 +1,507 @@ +/* + * EVIC.cpp + * + * Class to interface with the Electric Vehicle Interface Controller EVIC by Andromeda Interfaces. This Class + * will extract operating data from the GEVCU and send to EVIC via CAN message for display. + * It will also RECEIVE data from a JLD505 pack measurement unit if it is available and use that as a more + * accurate source for some data. + * + Copyright (c) 2015 Jack Rickard + + Permission is hereby granted, free of charge, to any person obtaining + a copy of this software and associated documentation files (the + "Software"), to deal in the Software without restriction, including + without limitation the rights to use, copy, modify, merge, publish, + distribute, sublicense, and/or sell copies of the Software, and to + permit persons to whom the Software is furnished to do so, subject to + the following conditions: + + The above copyright notice and this permission notice shall be included + in all copies or substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. + IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY + CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, + TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE + SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + */ + +#include "EVIC.h" + +//This just gives us a different way of printing to serial port by streaming. +template inline Print &operator <<(Print &obj, T arg) { obj.print(arg); return obj; } + + + +/* + * Constructor. + */ +EVIC::EVIC() : Device() +{ + prefsHandler = new PrefHandler(EVICTUS); + + commonName = "Andromeda Interfaces EVIC Display"; +} + + +/* + * Initialization of hardware and parameters + */ +void EVIC::setup() { + + Logger::info("add device: EVIC (id: %X, %X)", EVICTUS, this); + + TickHandler::getInstance()->detach(this);//Turn off tickhandler + + loadConfiguration(); //Retrieve any persistant variables + + Device::setup(); // run the parent class version of this function + + // register ourselves as observer of all 0x404 and 0x505 can frames from JLD505 + CanHandler::getInstanceCar()->attach(this, 0x404, 0x7ff, false); + CanHandler::getInstanceCar()->attach(this, 0x505, 0x7ff, false); + + MotorController* motorController = DeviceManager::getInstance()->getMotorController(); + nominalVolt=(motorController->nominalVolts); //Get default nominal volts and capacity from motorcontroller + capacity=(motorController->capacity);//If we do NOT have a JLD505, we will use these. + + tickCounter = 0; + testMode=0; + AHf=AH; + SOC=0; + SOCf=0.001; + milliAH=0.00; + DCV=0; + DCA=0; + TEMPM=0; + TEMPI=0; + CellHi=63; + Cello=60; + + elapsedtime=timemark = timemark2=millis(); + rpm=0; //Increment all our test variables each time + + TickHandler::getInstance()->attach(this, CFG_TICK_INTERVAL_EVIC); + +} + + +//This method handles particular received CAN frames we have registered for +void EVIC::handleCanFrame(CAN_FRAME *frame) +{ + + Logger::debug("EVIC received msg: %X %X %X %X %X %X %X %X %X", frame->id, frame->data.bytes[0], + frame->data.bytes[1],frame->data.bytes[2],frame->data.bytes[3],frame->data.bytes[4], + frame->data.bytes[5],frame->data.bytes[6],frame->data.bytes[7]); + + switch (frame->id) + { + + case 0x404: //Battery measurement message + dcVoltage= word(frame->data.bytes[0],frame->data.bytes[1]); + dcVoltage=dcVoltage; + dcCurrent= word(frame->data.bytes[2],frame->data.bytes[3]); + dcCurrent=dcCurrent; + AH= word(frame->data.bytes[4],frame->data.bytes[5]); + capacity=frame->data.bytes[6]; + SOC=frame->data.bytes[7]; + + + Logger::debug("JLD404 DC Voltage: %d Amps: %d AH: %d Capacity: %d SOC: %d", dcVoltage,dcCurrent,AH,capacity,SOC); + timemark=millis(); //We'll use this to indicate how long since we received from a 505. + break; + + case 0x505: //System Status Message + + Power= word(frame->data.bytes[0],frame->data.bytes[1]); + kWh= word(frame->data.bytes[2],frame->data.bytes[3]); + kWh=kWh/10; + celltemp1=frame->data.bytes[4]-40; + celltemp2=frame->data.bytes[5]-40; + celltemp3=frame->data.bytes[6]-40; + celltemp4=frame->data.bytes[7]-40; + + CellHi=Cello=celltemp1; + if(CellHicelltemp2){Cello=celltemp2;} //CellT to hold highest value + if(CellHicelltemp3){Cello=celltemp3;} //CellT to hold highest value + if(CellHicelltemp4){Cello=celltemp4;} //CellT to hold highest value + + + + Logger::debug("JLD505 Message Received Power output: %d kiloWatt-Hours: %d ", Power/10,kWh/10); + timemark=millis(); + break; + } +} + +//This method handles periodic tick calls received from the tasker. + +void EVIC::handleTick() +{ + + if(testMode==0) + { + sendCmdCurtis(); + sendCmdOrion(); + } + else + { + sendTestCmdCurtis(); + sendTestCmdOrion(); + } +} + + +/* +EVIC Curtis only HAS a single command CAN bus frame - address 0x601 Everything is stuffed into this one frame. It has an 8 byte payload. + +Curtis 250kbps Motorola byte order CAN_1 0x601 100ms Cyclic + +motor_rpm 8 16 1 0 -100 10000 rpm signed +motor_temp 16 8 1 0 -20 200 celsius signed +controller_temp 24 8 1 0 -20 200 celsius signed +motor_amps 40 16 0.1 0 -1000 2000 amps signed +motor_voltage 56 16 0.1 0 0 1000 volts signed +*/ + +void EVIC::sendTestCmdCurtis() +{ + rpm++; //Increment all our test variables each time + DCV++; + DCA++; + TEMPM++; + TEMPI++; + + CAN_FRAME output; + output.length = 8; + output.id = 0x601; + output.extended = 0; //standard frame + output.rtr = 0; + output.fid=0; + output.priority=0; + output.data.bytes[0] = highByte(rpm); + output.data.bytes[1] = lowByte(rpm); + output.data.bytes[2] = TEMPM; + output.data.bytes[3] = TEMPI; + output.data.bytes[4] = highByte(DCA); + output.data.bytes[5] = lowByte(DCA); + output.data.bytes[6] = highByte(DCV); + output.data.bytes[7] = lowByte(DCV); + + CanHandler::getInstanceCar()->sendFrame(output); //Mail it. + + timestamp(); + + Logger::debug("EVIC Message: %X %X %X %X %X %X %X %X %X %d:%d:%d.%d",output.id, output.data.bytes[0], +output.data.bytes[1],output.data.bytes[2],output.data.bytes[3],output.data.bytes[4],output.data.bytes[5],output.data.bytes[6],output.data.bytes[7], hours, minutes, seconds, milliseconds); + +} + +void EVIC::sendTestCmdOrion() +{ + AH--; + CAN_FRAME output; + output.length = 8; + output.id = 0x150; + output.extended = 0; //standard frame + output.rtr = 0; +output.fid=0; + output.data.bytes[0] = highByte(DCA); + output.data.bytes[1] = lowByte(DCA); + output.data.bytes[2] = highByte(DCV); + output.data.bytes[3] = lowByte(DCV); + output.data.bytes[4] = highByte(AH); + output.data.bytes[5] = lowByte(AH); //Pack capacity in tenths of ampere-hours + output.data.bytes[6] = 0; //Cell temp + output.data.bytes[7] = 0; //Cell temp + + CanHandler::getInstanceCar()->sendFrame(output); //Mail it. + timestamp(); + + Logger::debug("Orion Message1: %X %X %X %X %X %X %X %X %X %d:%d:%d.%d",output.id, output.data.bytes[0], +output.data.bytes[1],output.data.bytes[2],output.data.bytes[3],output.data.bytes[4],output.data.bytes[5],output.data.bytes[6],output.data.bytes[7], hours, minutes, seconds, milliseconds); + + //CAN_FRAME output; + output.length = 8; + output.id = 0x650; + output.extended = 0; //standard frame + output.rtr = 0; + output.fid=0; + output.data.bytes[0] = SOC--; //SOC in percent 0-100 + output.data.bytes[1] = 0; //pack internal resistance MSB + output.data.bytes[2] = 0; //pack internal resistance LSB + output.data.bytes[3] = 100;//pack health 0-100%; + output.data.bytes[4] = lowByte(DCV); + output.data.bytes[5] = highByte(DCV); + output.data.bytes[6] = 0; //pack cycles MSB + output.data.bytes[7] = 0; //pack cycles LSB + + CanHandler::getInstanceCar()->sendFrame(output); //Mail it. + timestamp(); + + Logger::debug("Orion Message2: %X %X %X %X %X %X %X %X %X %d:%d:%d.%d",output.id, output.data.bytes[0], +output.data.bytes[1],output.data.bytes[2],output.data.bytes[3],output.data.bytes[4],output.data.bytes[5],output.data.bytes[6],output.data.bytes[7], hours, minutes, seconds, milliseconds); + +} + +void EVIC::sendCmdCurtis() +{ + + MotorController* motorController = DeviceManager::getInstance()->getMotorController(); + + if(millis()-timemark>2000) + { + dcCurrent=motorController->getDcCurrent(); + dcVoltage=motorController->getDcVoltage(); + + } + CAN_FRAME output; + output.length = 8; + output.id = 0x601; + output.extended = 0; //standard frame + output.rtr = 0; + output.fid=0; + output.data.bytes[0] = highByte(motorController->getSpeedActual()); + output.data.bytes[1] = lowByte(motorController->getSpeedActual()); + output.data.bytes[2] = (motorController->getTemperatureMotor()/10); + output.data.bytes[3] = (motorController->getTemperatureInverter()/10); + output.data.bytes[4] = highByte(dcCurrent); + output.data.bytes[5] = lowByte(dcCurrent); + output.data.bytes[6] = highByte(dcVoltage); + output.data.bytes[7] = lowByte(dcVoltage); + + CanHandler::getInstanceCar()->sendFrame(output); //Mail it. + timestamp(); + Logger::debug("EVIC Message: %X %X %X %X %X %X %X %X %X %d:%d:%d.%d",output.id, output.data.bytes[0], +output.data.bytes[1],output.data.bytes[2],output.data.bytes[3],output.data.bytes[4],output.data.bytes[5],output.data.bytes[6],output.data.bytes[7], hours, minutes, seconds, milliseconds); + +} + +void EVIC::sendCmdOrion() +{ + elapsedtime = (millis() - timemark2); + timemark2=millis(); + + if(millis()-timemark>2000) // Checks to see how long its been since JLD505 message was received. + //If more than 2 seconds, we'll use MotorController values and calculate what we need. + { + MotorController* motorController = DeviceManager::getInstance()->getMotorController(); + dcCurrent=(motorController->getDcCurrent()); + dcVoltage=(motorController->getDcVoltage()); + + //dcVoltage=3320; //Test value + Logger::debug("DC Voltage: %i Nominal Voltage: %i Capacity: %i",dcVoltage/10,nominalVolt/10,capacity); + + if(!(dcVoltagesendFrame(output); //Mail it. + timestamp(); +Logger::debug("Orion Message1: %X %X %X %X %X %X %X %X %X %d:%d:%d.%d",output.id, output.data.bytes[0], +output.data.bytes[1],output.data.bytes[2],output.data.bytes[3],output.data.bytes[4],output.data.bytes[5],output.data.bytes[6],output.data.bytes[7], hours, minutes, seconds, milliseconds); + + //Assemble our 650 frame output; + output.length = 8; + output.id = 0x650; + output.extended = 0; //standard frame + output.rtr = 0; + output.fid=0; + + if(SOC>110){SOC=0;} + + output.data.bytes[0] = SOC*2; //SOC in percent 0-100 EVIC expects this as 0-200 with 200=100%. + output.data.bytes[1] = 0; //pack internal resistance MSB + output.data.bytes[2] = 0; //pack internal resistance LSB + output.data.bytes[3] = 100;//pack health 0-100%; + output.data.bytes[4] = highByte(dcVoltage); + output.data.bytes[5] = lowByte(dcVoltage); + output.data.bytes[6] = 0; //pack cycles MSB + output.data.bytes[7] = 0; //pack cycles LSB + + CanHandler::getInstanceCar()->sendFrame(output); //Mail it. + timestamp(); + Logger::debug("Orion Message2: %X %X %X %X %X %X %X %X %X %d:%d:%d.%d",output.id, output.data.bytes[0], +output.data.bytes[1],output.data.bytes[2],output.data.bytes[3],output.data.bytes[4],output.data.bytes[5],output.data.bytes[6],output.data.bytes[7], hours, minutes, seconds, milliseconds); + +} + + +void EVIC::timestamp() +{ + milliseconds = (int) (millis()/1) %1000 ; + seconds = (int) (millis() / 1000) % 60 ; + minutes = (int) ((millis() / (1000*60)) % 60); + hours = (int) ((millis() / (1000*60*60)) % 24); + // char buffer[9]; + //sprintf(buffer,"%02d:%02d:%02d.%03d", hours, minutes, seconds, milliseconds); + // Serial<checksumValid()) + { //checksum is good, read in the values stored in EEPROM + prefsHandler->read(EESYS_CAPACITY, &capacity); + prefsHandler->read(EESYS_AH, &AH); + + } + else + { + capacity = BatteryCapacity; //Get capacity value from config.h + prefsHandler->write(EESYS_CAPACITY, capacity); //and write it to EEPROM + // prefsHandler->write(EESYS_AH,AH); + prefsHandler->saveChecksum(); + } + + +} + +void EVIC::saveConfiguration() { + EVICConfiguration *config = (EVICConfiguration *)getConfiguration(); + + + //Device::saveConfiguration(); //call parent save routine + + prefsHandler->write(EESYS_CAPACITY, capacity); //save current values to EEPROM + prefsHandler->write(EESYS_AH, AH); //save current values to EEPROM + prefsHandler->saveChecksum(); + + loadConfiguration(); + +} + +int16_t EVIC::getdcVoltage() + { + return dcVoltage; + } +int16_t EVIC::getdcCurrent() + { + return dcCurrent; + } +uint16_t EVIC::getAH() + { + return AH; + } +uint8_t EVIC::getCapacity() + { + return capacity; + } +void EVIC::setCapacity(uint8_t capacity) + { + capacity=capacity; + } +uint8_t EVIC::getSOC() + { + return SOC; + } +int16_t EVIC::getPower() + { + return Power; + } +int16_t EVIC::getkWh() + { + return kWh; + } +int16_t EVIC::getTemperatureMotor() + { + return temperatureMotor; + } +int16_t EVIC::getTemperatureInverter() + { + return temperatureInverter; + } +int16_t EVIC::getRPM() + { + return rpm; + } +uint8_t EVIC::getCellTemp1() + { + return celltemp1; + } +uint8_t EVIC::getCellTemp2() + { + return celltemp2; + } +uint8_t EVIC::getCellTemp3() + { + return celltemp3; + } +uint8_t EVIC::getCellTemp4() + { + return celltemp4; + } +uint8_t EVIC::getCellHi() + { + return CellHi; + } +uint8_t EVIC::getCello() + { + return Cello; + } + + + + + diff --git a/EVIC.h b/EVIC.h new file mode 100644 index 0000000..e8c0726 --- /dev/null +++ b/EVIC.h @@ -0,0 +1,139 @@ +/* + * EVIC.h + * + * * Class to interface with the Electric Vehicle Interface Controller EVIC by Andromeda Interfaces. This Class will extract operating data from the GEVCU and send to EVIC via CAN message for display. + * + * + * Created: 1/28/2015 + * Author: Jack Rickard + + Copyright (c) 2015 Jack Rickard + +Permission is hereby granted, free of charge, to any person obtaining +a copy of this software and associated documentation files (the +"Software"), to deal in the Software without restriction, including +without limitation the rights to use, copy, modify, merge, publish, +distribute, sublicense, and/or sell copies of the Software, and to +permit persons to whom the Software is furnished to do so, subject to +the following conditions: + +The above copyright notice and this permission notice shall be included +in all copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, +EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF +MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. +IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY +CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, +TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE +SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. +*/ + +#ifndef EVIC_H_ +#define EVIC_H_ + +#include +#include "config.h" +#include "constants.h" +#include "Device.h" +#include "TickHandler.h" +#include "CanHandler.h" +#include "DeviceManager.h" +#include "Sys_Messages.h" +#include "DeviceTypes.h" + +extern PrefHandler *sysPrefs; + + +class EVICConfiguration: public DeviceConfiguration { +public: + //uint8_t capacity; +}; + + +class EVIC: public Device, CanObserver { + public: + + EVIC(); + //EVIC(USARTClass *which); + virtual void handleTick(); + virtual void handleCanFrame(CAN_FRAME *frame); + + virtual void setup(); //initialization on start up + void timestamp(); + DeviceType getType(); + DeviceId getId(); + + char *getTimeRunning(); + void loadConfiguration(); + void saveConfiguration(); + int16_t getdcVoltage(); + int16_t getdcCurrent(); + uint16_t getAH(); + uint8_t getCapacity(); + void setCapacity(uint8_t capacity); + uint8_t getSOC(); + int16_t getPower(); + int16_t getkWh(); + int16_t getTemperatureMotor(); + int16_t getTemperatureInverter(); + int16_t getRPM(); + uint8_t getCellTemp1(); + uint8_t getCellTemp2(); + uint8_t getCellTemp3(); + uint8_t getCellTemp4(); + uint8_t getCellHi(); + uint8_t getCello(); + + unsigned long timemark; + unsigned long timemark2; + int16_t torqueActual; + int16_t speedActual; + int16_t dcVoltage; + int16_t dcCurrent; + uint16_t nominalVolt; + uint16_t AH; + uint8_t capacity; + uint8_t SOC; + int16_t Power; + int16_t kWh; + int16_t temperatureMotor; + int16_t temperatureInverter; + int16_t rpm; + uint8_t celltemp1; + uint8_t celltemp2; + uint8_t celltemp3; + uint8_t celltemp4; + uint8_t CellHi; + uint8_t Cello; + + private: + void sendTestCmdCurtis(); + void sendTestCmdOrion(); + void sendCmdCurtis(); + void sendCmdOrion(); + + double AHf; + double milliAH; + float SOCf; + int milliseconds ; + int seconds; + int minutes; + int hours ; + unsigned long elapsedtime; + int16_t DCV; + int16_t DCA; + int8_t TEMPM; + int8_t TEMPI; + + int tickCounter; + char buffer[30]; // a buffer for various string conversions + uint32_t lastSentTime; + boolean weHave505; + boolean testMode; + + +}; + +#endif + diff --git a/FaultCodes.h b/FaultCodes.h index 1ac554a..12f14c3 100644 --- a/FaultCodes.h +++ b/FaultCodes.h @@ -168,4 +168,6 @@ enum FAULTCODE { }; -#endif \ No newline at end of file +#endif + + diff --git a/FaultHandler.cpp b/FaultHandler.cpp index ddc37c8..e1cfe1c 100644 --- a/FaultHandler.cpp +++ b/FaultHandler.cpp @@ -223,3 +223,5 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. } FaultHandler faultHandler; + + diff --git a/FaultHandler.h b/FaultHandler.h index ce1338d..aa595f5 100644 --- a/FaultHandler.h +++ b/FaultHandler.h @@ -80,3 +80,5 @@ class FaultHandler : public TickObserver { extern FaultHandler faultHandler; #endif /* FAULT_H_ */ + + diff --git a/GEVCU.h b/GEVCU.h index a2fc152..81d24d2 100644 --- a/GEVCU.h +++ b/GEVCU.h @@ -52,6 +52,8 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. #include "Sys_Messages.h" #include "CodaMotorController.h" #include "FaultHandler.h" +#include "DCDCController.h" +#include "EVIC.h" #ifdef __cplusplus extern "C" { @@ -68,3 +70,5 @@ void setup(); #define SYSTEM_GEVCU3 3 #endif /* GEVCU_H_ */ + + diff --git a/GEVCU.ino b/GEVCU.ino index ce0db35..e15e705 100644 --- a/GEVCU.ino +++ b/GEVCU.ino @@ -71,6 +71,7 @@ SerialConsole *serialConsole; Device *wifiDevice; Device *btDevice; + byte i = 0; @@ -86,8 +87,8 @@ void initWiReach() SerialUSB.begin(115200); // use SerialUSB only as the programming port doesn't work Serial2.begin(115200); // use Serial3 for GEVCU2, use Serial2 for GEVCU3+4 -sendWiReach("AT+iFD");//Host connection set to serial port -delay(5000); +//sendWiReach("AT+iFD");//Host connection set to serial port +//delay(5000); sendWiReach("AT+iHIF=1");//Host connection set to serial port sendWiReach("AT+iBDRF=9");//Automatic baud rate on host serial port sendWiReach("AT+iRPG=secret"); //Password for iChip wbsite @@ -215,13 +216,14 @@ void createObjects() { CanBrake *cbrake = new CanBrake(); DmocMotorController *dmotorController = new DmocMotorController(); CodaMotorController *cmotorController = new CodaMotorController(); + DCDCController *dcdcController = new DCDCController(); BrusaMotorController *bmotorController = new BrusaMotorController(); ThinkBatteryManager *BMS = new ThinkBatteryManager(); ELM327Emu *emu = new ELM327Emu(); ICHIPWIFI *iChip = new ICHIPWIFI(); + EVIC *eVIC = new EVIC(); } - -void initializeDevices() { + void initializeDevices() { DeviceManager *deviceManager = DeviceManager::getInstance(); //heartbeat is always enabled now @@ -270,7 +272,7 @@ void setup() { { Logger::info("Initializing EEPROM"); initSysEEPROM(); - initWiReach(); + // initWiReach(); } else {Logger::info("Using existing EEPROM values");}//checksum is good, read in the values stored in EEPROM @@ -321,3 +323,5 @@ void loop() { } + + diff --git a/GEVCU.vcxproj b/GEVCU.vcxproj index 2918951..7623a2b 100644 --- a/GEVCU.vcxproj +++ b/GEVCU.vcxproj @@ -64,10 +64,14 @@ - WIN32;NDEBUG;_CONSOLE;%(PreprocessorDefinitions) + printf=iprintf;F_CPU=84000000L;ARDUINO=165;ARDUINO_SAM_DUE;ARDUINO_ARCH_SAM;__SAM3X8E__;USB_VID=0x2341;USB_PID=0x003e;USBCON;__cplusplus;%(PreprocessorDefinitions) MultiThreadedDLL Level3 ProgramDatabase + C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\hardware\sam\1.6.4\cores\arduino;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\hardware\sam\1.6.4\variants\arduino_due_x;C:\Users\Collin\Desktop\GEVCU;C:\Users\Collin\Documents\Arduino\libraries\due_can;C:\Users\Collin\Documents\Arduino\libraries\due_can\utility;C:\Users\Collin\Documents\Arduino\libraries\due_rtc;C:\Users\Collin\Documents\Arduino\libraries\due_rtc\utility;C:\Users\Collin\Documents\Arduino\libraries\due_wire;C:\Users\Collin\Documents\Arduino\libraries\due_wire\utility;C:\Users\Collin\Documents\Arduino\libraries\DueTimer;C:\Users\Collin\Documents\Arduino\libraries\DueTimer\utility;c:\arduino-1.6.5-r2\libraries;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\hardware\sam\1.6.4\libraries;C:\Program Files (x86)\Visual Micro\Visual Micro for Arduino\Micro Platforms\default\debuggers;C:\Users\Collin\Documents\Arduino\libraries;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\hardware\sam\1.6.4\system/libsam;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\hardware\sam\1.6.4\system/CMSIS/CMSIS/Include/;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\hardware\sam\1.6.4\system/CMSIS/Device/ATMEL/;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\tools\arm-none-eabi-gcc\4.8.3-2014q1/arm-none-eabi/include/c++/4.8.3/arm-none-eabi/;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\tools\arm-none-eabi-gcc\4.8.3-2014q1/arm-none-eabi/include/;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\tools\arm-none-eabi-gcc\4.8.3-2014q1\lib\gcc\arm-none-eabi\4.8.3\include;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\hardware\sam\1.6.4\system\CMSIS\Device\ATMEL\;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\hardware\sam\1.6.4\system\libsam;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\hardware\sam\1.6.4\system\libsam\include;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\hardware\sam\1.6.4\system\CMSIS\CMSIS\Include\;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\hardware\sam\1.6.4\system\CMSIS\CMSIS\Include\;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\hardware\sam\1.6.4\system\CMSIS\Device\ATMEL\;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\hardware\sam\1.6.4\system\libsam;C:\Users\Collin\AppData\Roaming\arduino15\packages\arduino\hardware\sam\1.6.4\system\libsam\include;c:\arduino-1.6.5-r2/hardware/tools/g++_arm_none_eabi\arm-none-eabi\include;c:\arduino-1.6.5-r2/hardware/tools/g++_arm_none_eabi\arm_none_eabi\include\;c:\arduino-1.6.5-r2/hardware/tools/g++_arm_none_eabi\lib\gcc\arm-none-eabi\4.4.1\include;c:\arduino-1.6.5-r2/hardware/tools/g++_arm_none_eabi\lib\gcc\arm-none-eabi\4.4.1\include\;%(AdditionalIncludeDirectories) + C:\Users\Collin\Desktop\GEVCU\Visual Micro\.GEVCU.vsarduino.h;%(ForcedIncludeFiles) + true + Disabled MachineX86 @@ -91,6 +95,9 @@ CppCode + + CppCode + @@ -100,6 +107,9 @@ + + CppCode + @@ -142,11 +152,13 @@ + + diff --git a/GEVCU.vcxproj.filters b/GEVCU.vcxproj.filters index 7e5980b..183ec63 100644 --- a/GEVCU.vcxproj.filters +++ b/GEVCU.vcxproj.filters @@ -123,6 +123,12 @@ Header Files + + Header Files + + + Header Files + @@ -212,5 +218,11 @@ Source Files + + Source Files + + + Source Files + \ No newline at end of file diff --git a/Heartbeat.cpp b/Heartbeat.cpp index dafd0b4..1d55cf0 100644 --- a/Heartbeat.cpp +++ b/Heartbeat.cpp @@ -89,3 +89,5 @@ void Heartbeat::handleTick() { } } + + diff --git a/Heartbeat.h b/Heartbeat.h index 5439735..d2d21ad 100644 --- a/Heartbeat.h +++ b/Heartbeat.h @@ -50,3 +50,5 @@ class Heartbeat: public TickObserver { }; #endif /* HEARTBEAT_H_ */ + + diff --git a/Logger.cpp b/Logger.cpp index 84a6b31..7f2c509 100644 --- a/Logger.cpp +++ b/Logger.cpp @@ -370,3 +370,5 @@ void Logger::printDeviceName(DeviceId deviceId) { SerialUSB.print(" - "); } + + diff --git a/Logger.h b/Logger.h index 436a4e0..4ae6686 100644 --- a/Logger.h +++ b/Logger.h @@ -60,3 +60,5 @@ class Logger { }; #endif /* LOGGER_H_ */ + + diff --git a/MemCache.cpp b/MemCache.cpp index 3c94958..edb2e1d 100644 --- a/MemCache.cpp +++ b/MemCache.cpp @@ -402,3 +402,5 @@ boolean MemCache::cache_writepage(uint8_t page) Wire.endTransmission(true); return true; } + + diff --git a/MemCache.h b/MemCache.h index 8200ba4..545f9c7 100644 --- a/MemCache.h +++ b/MemCache.h @@ -99,3 +99,5 @@ class MemCache: public TickObserver { }; #endif /* MEM_CACHE_H_ */ + + diff --git a/MotorController.cpp b/MotorController.cpp index 67d6fdd..46d35d6 100644 --- a/MotorController.cpp +++ b/MotorController.cpp @@ -82,6 +82,7 @@ void MotorController::setup() { statusBitfield4 = 0; prefsHandler->read(EEMC_KILOWATTHRS, &kiloWattHours); //retrieve kilowatt hours from EEPROM nominalVolts=config->nominalVolt; + capacity=config->capacity; donePrecharge=false; premillis=millis(); @@ -565,12 +566,14 @@ void MotorController::loadConfiguration() { prefsHandler->read(EEMC_PRECHARGE_RELAY, &config->prechargeRelay); prefsHandler->read(EEMC_CONTACTOR_RELAY, &config->mainContactorRelay); prefsHandler->read(EEMC_COOL_FAN, &config->coolFan); - prefsHandler->read(EEMC_COOL_ON, &config->coolOn); - prefsHandler->read(EEMC_COOL_OFF, &config->coolOff); - prefsHandler->read(EEMC_BRAKE_LIGHT, &config->brakeLight); + prefsHandler->read(EEMC_COOL_ON, &config->coolOn); + prefsHandler->read(EEMC_COOL_OFF, &config->coolOff); + prefsHandler->read(EEMC_BRAKE_LIGHT, &config->brakeLight); prefsHandler->read(EEMC_REV_LIGHT, &config->revLight); prefsHandler->read(EEMC_ENABLE_IN, &config->enableIn); prefsHandler->read(EEMC_REVERSE_IN, &config->reverseIn); + prefsHandler->read(EESYS_CAPACITY, &config->capacity); + } else { //checksum invalid. Reinitialize values and store to EEPROM @@ -620,8 +623,11 @@ void MotorController::saveConfiguration() { prefsHandler->write(EEMC_REV_LIGHT, config->revLight); prefsHandler->write(EEMC_ENABLE_IN, config->enableIn); prefsHandler->write(EEMC_REVERSE_IN, config->reverseIn); + prefsHandler->write(EESYS_CAPACITY, config->capacity); - + prefsHandler->saveChecksum(); loadConfiguration(); } + + diff --git a/MotorController.h b/MotorController.h index 33901b9..693ca61 100644 --- a/MotorController.h +++ b/MotorController.h @@ -60,6 +60,7 @@ class MotorControllerConfiguration : public DeviceConfiguration { uint8_t revLight; uint8_t enableIn; uint8_t reverseIn; + uint8_t capacity; }; @@ -116,7 +117,8 @@ uint32_t statusBitfield1; // bitfield variable for use of the specific implement uint32_t statusBitfield2; uint32_t statusBitfield3; uint32_t statusBitfield4; - +uint32_t kiloWattHours; + @@ -162,7 +164,8 @@ uint32_t statusBitfield4; int minutes; int hours ; int premillis; - + uint16_t nominalVolts; //nominal pack voltage in 1/10 of a volt + uint8_t capacity; protected: @@ -190,15 +193,13 @@ uint32_t statusBitfield4; uint16_t dcVoltage; // DC voltage in 0.1 Volts int16_t dcCurrent; // DC current in 0.1 Amps uint16_t acCurrent; // AC current in 0.1 Amps - uint32_t kiloWattHours; int16_t mechanicalPower; // mechanical power of the motor 0.1 kW int16_t temperatureMotor; // temperature of motor in 0.1 degree C int16_t temperatureInverter; // temperature of inverter power stage in 0.1 degree C int16_t temperatureSystem; // temperature of controller in 0.1 degree C - uint16_t nominalVolts; //nominal pack voltage in 1/10 of a volt - + uint16_t prechargeTime; //time in ms that precharge should last uint32_t milliStamp; //how long we have precharged so far bool donePrecharge; //already completed the precharge cycle? @@ -207,3 +208,5 @@ uint32_t statusBitfield4; }; #endif + + diff --git a/OBD2Handler.cpp b/OBD2Handler.cpp index 86bcf54..8905811 100644 --- a/OBD2Handler.cpp +++ b/OBD2Handler.cpp @@ -222,3 +222,5 @@ bool OBD2Handler::processShowCustomData(uint16_t pid, char *inData, char *outDat } + + diff --git a/OBD2Handler.h b/OBD2Handler.h index 132b64e..2b7b5f3 100644 --- a/OBD2Handler.h +++ b/OBD2Handler.h @@ -56,4 +56,6 @@ class OBD2Handler { BatteryManager *BMS; }; -#endif \ No newline at end of file +#endif + + diff --git a/PotBrake.cpp b/PotBrake.cpp index ef77ac5..5c5ab31 100644 --- a/PotBrake.cpp +++ b/PotBrake.cpp @@ -170,6 +170,7 @@ void PotBrake::loadConfiguration() { prefsHandler->read(EETH_MAX_BRAKE_REGEN, &config->maximumRegen); prefsHandler->read(EETH_MIN_BRAKE_REGEN, &config->minimumRegen); prefsHandler->read(EETH_ADC_1, &config->AdcPin1); + config->AdcPin1 = 2; Logger::debug(POTBRAKEPEDAL, "BRAKE MIN: %l MAX: %l", config->minimumLevel1, config->maximumLevel1); Logger::debug(POTBRAKEPEDAL, "Min: %l MaxRegen: %l", config->minimumRegen, config->maximumRegen); } else { //checksum invalid. Reinitialize values and store to EEPROM @@ -201,3 +202,5 @@ void PotBrake::saveConfiguration() { prefsHandler->saveChecksum(); } + + diff --git a/PotBrake.h b/PotBrake.h index 000353c..15029a7 100644 --- a/PotBrake.h +++ b/PotBrake.h @@ -69,3 +69,5 @@ class PotBrake: public Throttle { }; #endif /* POT_BRAKE_H_ */ + + diff --git a/PotThrottle.cpp b/PotThrottle.cpp index 01593c2..6370e97 100644 --- a/PotThrottle.cpp +++ b/PotThrottle.cpp @@ -281,3 +281,5 @@ void PotThrottle::saveConfiguration() { prefsHandler->write(EETH_ADC_2, config->AdcPin2); prefsHandler->saveChecksum(); } + + diff --git a/PotThrottle.h b/PotThrottle.h index 194e9a5..c77ccef 100644 --- a/PotThrottle.h +++ b/PotThrottle.h @@ -76,3 +76,5 @@ class PotThrottle: public Throttle { }; #endif /* POT_THROTTLE_H_ */ + + diff --git a/PrefHandler.cpp b/PrefHandler.cpp index 3bd3860..61a304a 100644 --- a/PrefHandler.cpp +++ b/PrefHandler.cpp @@ -215,3 +215,5 @@ void PrefHandler::forceCacheWrite() memCache->FlushAllPages(); } + + diff --git a/PrefHandler.h b/PrefHandler.h index d70f072..f5f16f5 100644 --- a/PrefHandler.h +++ b/PrefHandler.h @@ -74,3 +74,5 @@ class PrefHandler { #endif + + diff --git a/SerialConsole.cpp b/SerialConsole.cpp index 89b038b..de439d4 100644 --- a/SerialConsole.cpp +++ b/SerialConsole.cpp @@ -98,7 +98,7 @@ void SerialConsole::printMenu() { SerialUSB.println("p = enable wifi passthrough (reboot required to resume normal operation)"); SerialUSB.println("S = show possible device IDs"); SerialUSB.println("w = GEVCU 4.2 reset wifi to factory defaults, setup GEVCU ad-hoc network"); - SerialUSB.println("W = GEVCU 5.2 reset wifi to factory defaults, setup GEVCU as 10.0.0.1 Access Point"); + SerialUSB.println("W = GEVCU 5.2 reset wifi to factory defaults, setup GEVCU as Access Point"); SerialUSB.println("s = Scan WiFi for nearby access points"); SerialUSB.println(); SerialUSB.println("Config Commands (enter command=newvalue). Current values shown in parenthesis:"); @@ -192,10 +192,11 @@ void SerialConsole::printMenu() { SerialUSB.println(); Logger::console("NOMV=%i - Fully charged pack voltage that automatically resets kWh counter", config->nominalVolt/10); + Logger::console("CAPACITY=%i - capacity of battery pack in ampere-hours", config->capacity); + Logger::console("kWh=%d - kiloWatt Hours of energy used", config->kilowattHrs/3600000); Logger::console("OUTPUT=<0-7> - toggles state of specified digital output"); - Logger::console("NUKE=1 - Resets all device settings in EEPROM. You have been warned."); - + Logger::console("NUKE=1 - Resets all device settings in EEPROM. You have been warned."); } @@ -244,10 +245,11 @@ void SerialConsole::handleConfigCmd() { PotThrottleConfiguration *acceleratorConfig = NULL; PotThrottleConfiguration *brakeConfig = NULL; MotorControllerConfiguration *motorConfig = NULL; + Throttle *accelerator = DeviceManager::getInstance()->getAccelerator(); Throttle *brake = DeviceManager::getInstance()->getBrake(); MotorController *motorController = DeviceManager::getInstance()->getMotorController(); - int i; + int i; int newValue; bool updateWifi = true; @@ -549,7 +551,21 @@ void SerialConsole::handleConfigCmd() { Logger::console("DOUT0:%d, DOUT1:%d, DOUT2:%d, DOUT3:%d, DOUT4:%d, DOUT5:%d, DOUT6:%d, DOUT7:%d", getOutput(0), getOutput(1), getOutput(2), getOutput(3), getOutput(4), getOutput(5), getOutput(6), getOutput(7)); - } else if (cmdString == String("NUKE")) { + + } else if (cmdString == String("CAPACITY") ) { + motorConfig->capacity = newValue; + motorController->saveConfiguration(); + Logger::console("Battery Pack Capacity set to: %d",motorConfig->capacity); + + } else if (cmdString == String("KWH") ) { + + motorController->kiloWattHours = newValue*3600000; + motorController->saveConfiguration(); + Logger::console("kWh set to: %d",motorController->kiloWattHours); + + + + } else if (cmdString == String("NUKE")) { if (newValue == 1) { //write zero to the checksum location of every device in the table. //Logger::console("Start of EEPROM Nuke"); @@ -561,7 +577,7 @@ void SerialConsole::handleConfigCmd() { } Logger::console("Device settings have been nuked. Reboot to reload default settings"); } - } else { + } else { Logger::console("Unknown command"); updateWifi = false; } @@ -685,19 +701,8 @@ void SerialConsole::handleShortCmd() { deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"RP20"); break; case 'W': - Logger::console("Setting Wifi Adapter to WPS mode (make sure you press the WPS button on your router)"); - // restore factory defaults and give it some time - deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"AWPS"); - break; - case 'w': - Logger::console("Resetting wifi to factory defaults and setting up GEVCU4.2 Ad Hoc network"); - // restore factory defaults and give it some time - // pinMode(43,OUTPUT); - // digitalWrite(43, LOW); //Pin 43 held low for 5 seconds puts Version 4.2 in Recovery mode - // delay(6000); - // digitalWrite(43, HIGH); - // delay(3000); - deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"FD");//Reset + Logger::console("Resetting wifi to factory defaults and setting up GEVCU5.2 Access Point"); + deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"FD");//Reset delay(2000); deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"HIF=1"); //Set for RS-232 serial. delay(1000); @@ -705,8 +710,12 @@ void SerialConsole::handleShortCmd() { delay(1000); deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"WLCH=9"); //use whichever channel an AP wants to use delay(1000); - deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"WLSI=!GEVCU"); //set for GEVCU aS AP. + deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"WLSI=GEVCU"); //set for GEVCU aS AP. + delay(1000); + + deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"STAP=1"); //enable IP delay(1000); + deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DIP=192.168.3.10"); //enable IP delay(1000); deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DPSZ=8"); //set DHCP server for 8 @@ -721,11 +730,64 @@ void SerialConsole::handleShortCmd() { delay(5000); // a 5 second delay is required for the chip to come back up ! Otherwise commands will be lost deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_CONFIG_CHANGE, NULL); // reload configuration params as they were lost - Logger::console("Wifi 4.2 initialized"); - break; - + Logger::console("Wifi 5.2 initialized"); + break; + case 'w': + Logger::console("Resetting wifi to factory defaults and setting up GEVCU4.2 Ad Hoc network"); + resetWiReachMini(); + deviceManager->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_CONFIG_CHANGE, NULL); // reload configuration params as they were lost + break; + case 'X': setup(); //this is probably a bad idea. Do not do this while connected to anything you care about - only for debugging in safety! break; } } + +void SerialConsole::resetWiReachMini() { + + //Serial2.begin(115200); + while (Serial2.available()) { + SerialUSB.write(Serial2.read()); + } + Serial2.println("AT+iFD"); + getResponse(); + Serial2.println("AT+iHIF=1"); + getResponse(); + Serial2.println("AT+iBDRA"); + getResponse(); + Serial2.println("AT+iWLCH=9"); + getResponse(); + Serial2.println("AT+iWLSI=!GEVCU"); + getResponse(); + Serial2.println("AT+iDIP=192.168.3.10"); + getResponse(); + Serial2.println("AT+iDPSZ=8"); + getResponse(); + Serial2.println("AT+iRPG=secret"); + getResponse(); + Serial2.println("AT+iWPWD=secret"); + getResponse(); + Serial2.println("AT+iAWS=1"); + getResponse(); + Serial2.println("AT+iDOWN"); + getResponse(); + getResponse(); + + + + Logger::console("Wifi 4.2 initialized"); +} + +void SerialConsole::getResponse(){ + + while (Serial2.available()) { + SerialUSB.write(Serial2.read()); + } + SerialUSB.println(); + delay(4000); + +} + + + diff --git a/SerialConsole.h b/SerialConsole.h index d6169ff..5a978ed 100644 --- a/SerialConsole.h +++ b/SerialConsole.h @@ -68,6 +68,10 @@ class SerialConsole { void handleConsoleCmd(); void handleShortCmd(); void handleConfigCmd(); + void resetWiReachMini(); + void getResponse(); }; #endif /* SERIALCONSOLE_H_ */ + + diff --git a/Shield/Ampseal.lbr b/Shield/Ampseal.lbr old mode 100644 new mode 100755 diff --git a/Shield/Analog_Board.brd b/Shield/Analog_Board.brd old mode 100644 new mode 100755 diff --git a/Shield/Analog_Board.sch b/Shield/Analog_Board.sch old mode 100644 new mode 100755 diff --git a/Shield/Analog_Shield.brd b/Shield/Analog_Shield.brd old mode 100644 new mode 100755 diff --git a/Shield/Analog_Shield.sch b/Shield/Analog_Shield.sch old mode 100644 new mode 100755 diff --git a/Shield/Canbus-Proto.brd b/Shield/Canbus-Proto.brd old mode 100644 new mode 100755 diff --git a/Shield/Canbus-Proto.sch b/Shield/Canbus-Proto.sch old mode 100644 new mode 100755 diff --git a/Shield/Canbus-proto2.brd b/Shield/Canbus-proto2.brd old mode 100644 new mode 100755 diff --git a/Shield/Eagle_Dued_autorouted.brd b/Shield/Eagle_Dued_autorouted.brd old mode 100644 new mode 100755 diff --git a/Shield/Eagle_Dued_autorouted.sch b/Shield/Eagle_Dued_autorouted.sch old mode 100644 new mode 100755 diff --git a/Shield/GEVCU-4.brd b/Shield/GEVCU-4.brd old mode 100644 new mode 100755 diff --git a/Shield/GEVCU-4.sch b/Shield/GEVCU-4.sch old mode 100644 new mode 100755 diff --git a/Shield/canbus-proto2.sch b/Shield/canbus-proto2.sch old mode 100644 new mode 100755 diff --git a/Shield/ck_custom.lbr b/Shield/ck_custom.lbr old mode 100644 new mode 100755 diff --git a/Shield/dc-dc-converter.lbr b/Shield/dc-dc-converter.lbr old mode 100644 new mode 100755 diff --git a/Sys_Messages.h b/Sys_Messages.h index 2034418..6b14796 100644 --- a/Sys_Messages.h +++ b/Sys_Messages.h @@ -39,3 +39,5 @@ enum SystemMessage { }; #endif + + diff --git a/ThinkBatteryManager.cpp b/ThinkBatteryManager.cpp index 7af69cd..3cc9597 100644 --- a/ThinkBatteryManager.cpp +++ b/ThinkBatteryManager.cpp @@ -191,3 +191,5 @@ bool ThinkBatteryManager::isDischargeOK() return allowDischarge; } + + diff --git a/ThinkBatteryManager.h b/ThinkBatteryManager.h index 887e81d..3c2c7e4 100644 --- a/ThinkBatteryManager.h +++ b/ThinkBatteryManager.h @@ -55,3 +55,5 @@ class ThinkBatteryManager : public BatteryManager, CanObserver }; #endif + + diff --git a/Throttle.cpp b/Throttle.cpp index 96b5c7a..972a3ec 100644 --- a/Throttle.cpp +++ b/Throttle.cpp @@ -231,3 +231,5 @@ void Throttle::saveConfiguration() { Logger::console("Throttle configuration saved"); } + + diff --git a/Throttle.h b/Throttle.h index 604d45e..57f5d35 100644 --- a/Throttle.h +++ b/Throttle.h @@ -98,3 +98,5 @@ class Throttle: public Device { }; #endif + + diff --git a/ThrottleDetector.cpp b/ThrottleDetector.cpp index 29074e4..b6fdc04 100644 --- a/ThrottleDetector.cpp +++ b/ThrottleDetector.cpp @@ -388,3 +388,5 @@ uint16_t ThrottleDetector::normalize(uint16_t sensorValue, uint16_t sensorMin, u int value = map(sensorValue, sensorMin, sensorMax, constrainMin, constrainMax); return constrain(value, constrainMin, constrainMax); } + + diff --git a/ThrottleDetector.h b/ThrottleDetector.h index 0abbc7b..647989f 100644 --- a/ThrottleDetector.h +++ b/ThrottleDetector.h @@ -99,3 +99,5 @@ class ThrottleDetector : public TickObserver { #endif /* THROTTLE_DETECTOR_H_ */ + + diff --git a/TickHandler.cpp b/TickHandler.cpp index 1e96c01..2e3de3f 100644 --- a/TickHandler.cpp +++ b/TickHandler.cpp @@ -250,3 +250,5 @@ void timer8Interrupt() { void TickObserver::handleTick() { Logger::error("TickObserver does not implement handleTick()"); } + + diff --git a/TickHandler.h b/TickHandler.h index a54b1c0..cbf8507 100644 --- a/TickHandler.h +++ b/TickHandler.h @@ -83,3 +83,5 @@ void timer7Interrupt(); void timer8Interrupt(); #endif /* TICKHANDLER_H_ */ + + diff --git a/config.h b/config.h index f10926c..4c5ea1c 100644 --- a/config.h +++ b/config.h @@ -35,8 +35,8 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. #include -#define CFG_BUILD_NUM 1051 //increment this every time a git commit is done. -#define CFG_VERSION "GEVCU 2014-09-16" +#define CFG_BUILD_NUM 5220 //increment this every time a git commit is done. +#define CFG_VERSION "GEVCU 2015-02-19" /* @@ -67,15 +67,17 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. #define CFG_TICK_INTERVAL_MEM_CACHE 40000 #define CFG_TICK_INTERVAL_BMS_THINK 500000 #define CFG_TICK_INTERVAL_WIFI 200000 +#define CFG_TICK_INTERVAL_DCDC 200000 +#define CFG_TICK_INTERVAL_EVIC 100000 /* * CAN BUS CONFIGURATION */ #define CFG_CAN0_SPEED CAN_BPS_500K // specify the speed of the CAN0 bus (EV) -#define CFG_CAN1_SPEED CAN_BPS_500K // specify the speed of the CAN1 bus (Car) -#define CFG_CAN0_NUM_RX_MAILBOXES 7 // amount of CAN bus receive mailboxes for CAN0 -#define CFG_CAN1_NUM_RX_MAILBOXES 7 // amount of CAN bus receive mailboxes for CAN1 +#define CFG_CAN1_SPEED CAN_BPS_250K // specify the speed of the CAN1 bus (Car) +#define CFG_CAN0_NUM_RX_MAILBOXES 9 // amount of CAN bus receive mailboxes for CAN0 +#define CFG_CAN1_NUM_RX_MAILBOXES 9 // amount of CAN bus receive mailboxes for CAN1 #define CFG_CANTHROTTLE_MAX_NUM_LOST_MSG 3 // maximum number of lost messages allowed /* @@ -115,16 +117,16 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. #define BrakeADC 2 //which ADC pin to use -#define MaxTorqueValue 3000 //in tenths of a Nm +#define MaxTorqueValue 3000 //in tenths of a Nm #define MaxRPMValue 6000 //DMOC will ignore this but we can use it ourselves for limiting -#define RPMSlewRateValue 10000 // rpm/sec the requested speed should change (speed mode) -#define TorqueSlewRateValue 6000 // 0.1Nm/sec the requested torque output should change (torque mode) +#define RPMSlewRateValue 10000 // rpm/sec the requested speed should change (speed mode) +#define TorqueSlewRateValue 6000 // 0.1Nm/sec the requested torque output should change (torque mode) #define KilowattHrs 11000 //not currently used #define PrechargeR 3000 //millliseconds precharge #define NominalVolt 3300 //a reasonable figure for a lithium cell pack driving the DMOC (in tenths of a volt) -#define PrechargeRelay 4 //third output -#define MainContactorRelay 5 //fourth output -#define ReversePercent 50 +#define PrechargeRelay 4 //third output +#define MainContactorRelay 5 //fourth output +#define ReversePercent 50 #define CoolFan 255 //output to use for cooling fan #define CoolOn 40 //temperature (in C) to turn on cooling fan #define BrakeLight 255 //temperature to turn it off @@ -132,8 +134,9 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. #define RevLight 255 //temperature to turn it off #define EnableIn 255//temperature to turn it off #define ReverseIn 255 //temperature to turn it off -#define MaxRegenWatts 40000 //in actual watts, there is no scale here -#define MaxAccelWatts 150000 +#define MaxRegenWatts 40000 //in actual watts, there is no scale here +#define MaxAccelWatts 150000 +#define BatteryCapacity 100 /* @@ -142,9 +145,9 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. * Define the maximum number of various object lists. * These values should normally not be changed. */ -#define CFG_DEV_MGR_MAX_DEVICES 20 // the maximum number of devices supported by the DeviceManager -#define CFG_CAN_NUM_OBSERVERS 5 // maximum number of device subscriptions per CAN bus -#define CFG_TIMER_NUM_OBSERVERS 9 // the maximum number of supported observers per timer +#define CFG_DEV_MGR_MAX_DEVICES 30 // the maximum number of devices supported by the DeviceManager +#define CFG_CAN_NUM_OBSERVERS 7 // maximum number of device subscriptions per CAN bus +#define CFG_TIMER_NUM_OBSERVERS 7 // the maximum number of supported observers per timer #define CFG_TIMER_USE_QUEUING // if defined, TickHandler uses a queuing buffer instead of direct calls from interrupts #define CFG_TIMER_BUFFER_SIZE 100 // the size of the queuing buffer for TickHandler #define CFG_FAULT_HISTORY_SIZE 50 //number of faults to store in eeprom. A circular buffer so the last 50 faults are always stored. @@ -159,4 +162,14 @@ SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. #define NUM_DIGITAL 4 #define NUM_OUTPUT 8 +//CAN message ID ASSIGNMENTS FOR I/0 MANAGEMENT +#define CAN_SWITCH 0x606 +#define CAN_OUTPUTS 0x607 +#define CAN_ANALOG_INPUTS 0x608 +#define CAN_DIGITAL_INPUTS 0x609 + + + #endif /* CONFIG_H_ */ + + diff --git a/constants.h b/constants.h index 030d5be..df5263c 100644 --- a/constants.h +++ b/constants.h @@ -105,3 +105,5 @@ namespace Constants { } #endif /* CONSTANTS_H_ */ + + diff --git a/docs/Design Drawings.vsd b/docs/Design Drawings.vsd old mode 100644 new mode 100755 diff --git a/docs/GEVCU pinout.txt b/docs/GEVCU pinout.txt old mode 100644 new mode 100755 diff --git a/docs/GEVCU-35pinout.jpg b/docs/GEVCU-35pinout.jpg old mode 100644 new mode 100755 diff --git a/docs/GEVCU1-1.03.docx b/docs/GEVCU1-1.03.docx old mode 100644 new mode 100755 diff --git a/docs/ThrottleFiltering.xlsx b/docs/ThrottleFiltering.xlsx old mode 100644 new mode 100755 diff --git a/docs/UQMplug.jpg b/docs/UQMplug.jpg old mode 100644 new mode 100755 diff --git a/docs/gevcumanual403.docx b/docs/gevcumanual403.docx old mode 100644 new mode 100755 diff --git a/docs/howtocreatemodule.docx b/docs/howtocreatemodule.docx new file mode 100755 index 0000000..978d2b0 Binary files /dev/null and b/docs/howtocreatemodule.docx differ diff --git a/eeprom_layout.h b/eeprom_layout.h index 18ad701..2df58a2 100644 --- a/eeprom_layout.h +++ b/eeprom_layout.h @@ -68,46 +68,46 @@ the end of the stardard data. The below numbers are offsets from the device's ee #define EE_DEVICE_ID 1 //2 bytes - the value of the ENUM DEVID of this device. //Motor controller data -#define EEMC_MAX_RPM 20 //2 bytes, unsigned int for maximum allowable RPM -#define EEMC_MAX_TORQUE 22 //2 bytes, unsigned int - maximum torque in tenths of a Nm +#define EEMC_MAX_RPM 20 //2 bytes, unsigned int for maximum allowable RPM +#define EEMC_MAX_TORQUE 22 //2 bytes, unsigned int - maximum torque in tenths of a Nm #define EEMC_PRECHARGE_RELAY 24 //1 byte - 255 = no precharge relay 0-3 = yes, there is one (and the output is the number stored) #define EEMC_CONTACTOR_RELAY 25 //1 byte - 255 = no contactor relay 0-3 = yes there is -#define EEMC_COOL_FAN 26 //1 byte output controlling external cooling relay -#define EEMC_COOL_ON 27 //1 bytes temperature at which external cooling is switched on -#define EEMC_COOL_OFF 28 //1 byte temperature at which external cooling is switched off -#define EEMC_KILOWATTHRS 29 //4 bytes - capacitance of controller capacitor bank in micro farads (uf) - set to zero to disable RC precharge -#define EEMC_PRECHARGE_R 33 //2 bytes - Resistance of precharge resistor in tenths of an ohm -#define EEMC_NOMINAL_V 35 //2 bytes - nominal system voltage to expect (in tenths of a volt) -#define EEMC_REVERSE_LIMIT 37 //2 bytes - a percentage to knock the requested torque down by while in reverse. -#define EEMC_RPM_SLEW_RATE 39 //2 bytes - slew rate (rpm/sec) at which speed should change (only in speed mode) +#define EEMC_COOL_FAN 26 //1 byte output controlling external cooling relay +#define EEMC_COOL_ON 27 //1 bytes temperature at which external cooling is switched on +#define EEMC_COOL_OFF 28 //1 byte temperature at which external cooling is switched off +#define EEMC_KILOWATTHRS 29 //4 bytes - capacitance of controller capacitor bank in micro farads (uf) - set to zero to disable RC precharge +#define EEMC_PRECHARGE_R 33 //2 bytes - Resistance of precharge resistor in tenths of an ohm +#define EEMC_NOMINAL_V 35 //2 bytes - nominal system voltage to expect (in tenths of a volt) +#define EEMC_REVERSE_LIMIT 37 //2 bytes - a percentage to knock the requested torque down by while in reverse. +#define EEMC_RPM_SLEW_RATE 39 //2 bytes - slew rate (rpm/sec) at which speed should change (only in speed mode) #define EEMC_TORQUE_SLEW_RATE 41 //2 bytes - slew rate (0.1Nm/sec) at which the torque should change #define EEMC_BRAKE_LIGHT 42 -#define EEMC_REV_LIGHT 43 -#define EEMC_ENABLE_IN 44 -#define EEMC_REVERSE_IN 45 -#define EEMC_MOTOR_MODE 46 +#define EEMC_REV_LIGHT 43 +#define EEMC_ENABLE_IN 44 +#define EEMC_REVERSE_IN 45 +#define EEMC_MOTOR_MODE 46 //throttle data -#define EETH_MIN_ONE 20 //2 bytes - ADC value of minimum value for first channel -#define EETH_MAX_ONE 22 //2 bytes - ADC value of maximum value for first channel -#define EETH_MIN_TWO 24 //2 bytes - ADC value of minimum value for second channel -#define EETH_MAX_TWO 26 //2 bytes - ADC value of maximum value for second channel +#define EETH_MIN_ONE 20 //2 bytes - ADC value of minimum value for first channel +#define EETH_MAX_ONE 22 //2 bytes - ADC value of maximum value for first channel +#define EETH_MIN_TWO 24 //2 bytes - ADC value of minimum value for second channel +#define EETH_MAX_TWO 26 //2 bytes - ADC value of maximum value for second channel #define EETH_REGEN_MIN 28 //2 bytes - unsigned int - tenths of a percent (0-1000) of pedal position where regen stops -#define EETH_FWD 30 //2 bytes - unsigned int - tenths of a percent (0-1000) of pedal position where forward motion starts -#define EETH_MAP 32 //2 bytes - unsigned int - tenths of a percent (0-1000) of pedal position where forward motion is at 50% throttle -#define EETH_BRAKE_MIN 34 //2 bytes - ADC value of minimum value for brake input -#define EETH_BRAKE_MAX 36 //2 bytes - ADC value of max value for brake input +#define EETH_FWD 30 //2 bytes - unsigned int - tenths of a percent (0-1000) of pedal position where forward motion starts +#define EETH_MAP 32 //2 bytes - unsigned int - tenths of a percent (0-1000) of pedal position where forward motion is at 50% throttle +#define EETH_BRAKE_MIN 34 //2 bytes - ADC value of minimum value for brake input +#define EETH_BRAKE_MAX 36 //2 bytes - ADC value of max value for brake input #define EETH_MAX_ACCEL_REGEN 38 //2 bytes - maximum percentage of throttle to command on accel pedal regen #define EETH_MAX_BRAKE_REGEN 40 //2 bytes - maximum percentage of throttle to command for braking regen. Starts at min brake regen and works up to here. -#define EETH_NUM_THROTTLES 42 //1 byte - How many throttle inputs should we use? (1 or 2) -#define EETH_THROTTLE_TYPE 43 //1 byte - Allow for different throttle types. For now 1 = Linear pots, 2 = Inverse relationship between pots. See Throttle.h +#define EETH_NUM_THROTTLES 42 //1 byte - How many throttle inputs should we use? (1 or 2) +#define EETH_THROTTLE_TYPE 43 //1 byte - Allow for different throttle types. For now 1 = Linear pots, 2 = Inverse relationship between pots. See Throttle.h #define EETH_MIN_BRAKE_REGEN 44 //2 bytes - the starting level for brake regen as a percentage of throttle #define EETH_MIN_ACCEL_REGEN 46 //2 bytes - the starting level for accelerator regen as a percentage of throttle #define EETH_REGEN_MAX 48 //2 bytes - unsigned int - tenths of a percent (0-1000) of pedal position where regen is at maximum -#define EETH_CREEP 50 //2 bytes - percentage of throttle used to simulate creep -#define EETH_CAR_TYPE 52 //1 byte - type of car for querying the throttle position via CAN bus -#define EETH_ADC_1 53 //1 byte - which ADC port to use for first throttle input -#define EETH_ADC_2 54 //1 byte - which ADC port to use for second throttle input +#define EETH_CREEP 50 //2 bytes - percentage of throttle used to simulate creep +#define EETH_CAR_TYPE 52 //1 byte - type of car for querying the throttle position via CAN bus +#define EETH_ADC_1 53 //1 byte - which ADC port to use for first throttle input +#define EETH_ADC_2 54 //1 byte - which ADC port to use for second throttle input //System Data #define EESYS_SYSTEM_TYPE 10 //1 byte - 1 = Old school protoboards 2 = GEVCU2/DUED 3 = GEVCU3 - Defaults to 2 if invalid or not set up @@ -154,6 +154,8 @@ the end of the stardard data. The below numbers are offsets from the device's ee #define EESYS_CAN_FILTER5 244 //4 bytes - sixth canbus filter - not valid on Macchina, Mask 5 on Due #define EESYS_CAN_MASK6 248 //4 bytes - seventh canbus mask - bit 31 sets whether it is extended or not (set = extended) #define EESYS_CAN_FILTER6 252 //4 bytes - seventh canbus filter - not valid on Macchina, Mask 6 on Due +#define EESYS_CAPACITY 256 // 1 byte - battery pack capacity in AH +#define EESYS_AH 257 // 2 bytes - current cumulative ampere hours //Allow for a few defined WIFI SSIDs that the GEVCU will try to automatically connect to. #define EESYS_WIFI0_SSID 300 //32 bytes - the SSID to create or use (prefixed with ! if create ad-hoc) @@ -170,33 +172,35 @@ the end of the stardard data. The below numbers are offsets from the device's ee #define EESYS_WIFI1_IPADDR 435 //4 bytes - IP address to use if DHCP is off #define EESYS_WIFI1_KEY 439 //40 bytes - the security key (13 bytes for WEP, 8 - 83 for WPA but only up to 40 here -#define EESYS_WIFI2_SSID 500 //32 bytes - the SSID to create or use (prefixed with ! if create ad-hoc) -#define EESYS_WIFI2_CHAN 532 //1 byte - the wifi channel (1 - 11) to use -#define EESYS_WIFI2_DHCP 533 //1 byte - DHCP mode, 0 = off, 1 = server, 2 = client -#define EESYS_WIFI2_MODE 534 //1 byte - 0 = B, 1 = G -#define EESYS_WIFI2_IPADDR 535 //4 bytes - IP address to use if DHCP is off -#define EESYS_WIFI2_KEY 539 //40 bytes - the security key (13 bytes for WEP, 8 - 83 for WPA but only up to 40 here +#define EESYS_WIFI2_SSID 500 //32 bytes - the SSID to create or use (prefixed with ! if create ad-hoc) +#define EESYS_WIFI2_CHAN 532 //1 byte - the wifi channel (1 - 11) to use +#define EESYS_WIFI2_DHCP 533 //1 byte - DHCP mode, 0 = off, 1 = server, 2 = client +#define EESYS_WIFI2_MODE 534 //1 byte - 0 = B, 1 = G +#define EESYS_WIFI2_IPADDR 535 //4 bytes - IP address to use if DHCP is off +#define EESYS_WIFI2_KEY 539 //40 bytes - the security key (13 bytes for WEP, 8 - 83 for WPA but only up to 40 here //If the above networks can't be joined then try to form our own adhoc network //with the below parameters. -#define EESYS_WIFIX_SSID 579 //32 bytes - the SSID to create or use (prefixed with ! if create ad-hoc) -#define EESYS_WIFIX_CHAN 611 //1 byte - the wifi channel (1 - 11) to use -#define EESYS_WIFIX_DHCP 612 //1 byte - DHCP mode, 0 = off, 1 = server, 2 = client +#define EESYS_WIFIX_SSID 579 //32 bytes - the SSID to create or use (prefixed with ! if create ad-hoc) +#define EESYS_WIFIX_CHAN 611 //1 byte - the wifi channel (1 - 11) to use +#define EESYS_WIFIX_DHCP 612 //1 byte - DHCP mode, 0 = off, 1 = server, 2 = client #define EESYS_WIFIX_MODE 613 //1 byte - 0 = B, 1 = G #define EESYS_WIFIX_IPADDR 614 //4 bytes - IP address to use if DHCP is off #define EESYS_WIFIX_KEY 618 //40 bytes - the security key (13 bytes for WEP, 8 - 83 for WPA but only up to 40 here #define EESYS_LOG_LEVEL 658 //1 byte - the log level -#define EESYS_AMPHOURS 659 //1 byte - ??? -#define EESYS_BRAKELIGHT 660 //1 byte - -#define EESYS_xxxx 661 //1 byte - - -#define EEFAULT_VALID 0 //1 byte - Set to value of 0xB2 if fault data has been initialized -#define EEFAULT_READPTR 1 //2 bytes - index where reading should start (first unacknowledged fault) -#define EEFAULT_WRITEPTR 3 //2 bytes - index where writing should occur for new faults -#define EEFAULT_RUNTIME 5 //4 bytes - stores the number of seconds (in tenths) that the system has been turned on for - total time ever +#define EESYS_AMPHOURS 659 //1 byte - ??? +#define EESYS_BRAKELIGHT 660 //1 byte - +#define EESYS_xxxx 661 //1 byte - + +#define EEFAULT_VALID 0 //1 byte - Set to value of 0xB2 if fault data has been initialized +#define EEFAULT_READPTR 1 //2 bytes - index where reading should start (first unacknowledged fault) +#define EEFAULT_WRITEPTR 3 //2 bytes - index where writing should occur for new faults +#define EEFAULT_RUNTIME 5 //4 bytes - stores the number of seconds (in tenths) that the system has been turned on for - total time ever #define EEFAULT_FAULTS_START 10 //a bunch of faults stored one after the other start at this location #endif + + diff --git a/ichip_2128.cpp b/ichip_2128.cpp index c250f59..fed521b 100644 --- a/ichip_2128.cpp +++ b/ichip_2128.cpp @@ -290,6 +290,7 @@ void ICHIPWIFI::handleTick() { paramCache.mainContactorRelay = motorController->getmainContactorRelay(); setParam(Constants::mainContactorRelay, (uint8_t) paramCache.mainContactorRelay); } + //DeviceManager::getInstance()->updateWifi(); } } else if (tickCounter == 3) { if (motorController) { @@ -786,57 +787,72 @@ void ICHIPWIFI::processParameterChange(char *key) { } else if (!strcmp(key, "x1000")){ if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16),true);} else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} - sysPrefs->forceCacheWrite(); - // Logger::console("Setting Device: %s ID:%X value %X",key, strtol(key+1, 0, 16),atol(value)); - + //sysPrefs->forceCacheWrite(); } else if (!strcmp(key, "x1001")){ if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16),true);} else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} - sysPrefs->forceCacheWrite(); + //sysPrefs->forceCacheWrite(); } else if (!strcmp(key, "x1002")){ if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16),true);} else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} - sysPrefs->forceCacheWrite(); + // sysPrefs->forceCacheWrite(); } else if (!strcmp(key, "x1031")){ if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);} else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} - sysPrefs->forceCacheWrite(); + //sysPrefs->forceCacheWrite(); } else if (!strcmp(key, "x1032")){ if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);} else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} - sysPrefs->forceCacheWrite(); + //sysPrefs->forceCacheWrite(); } else if (!strcmp(key, "x1033")){ if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);} else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} - sysPrefs->forceCacheWrite(); + //sysPrefs->forceCacheWrite(); } else if (!strcmp(key, "x1034")){ if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);} else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} - sysPrefs->forceCacheWrite(); + // sysPrefs->forceCacheWrite(); } else if (!strcmp(key, "x1010")){ if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);} else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} - sysPrefs->forceCacheWrite(); - } else if (!strcmp(key, "x1020")){ + // sysPrefs->forceCacheWrite(); + } else if (!strcmp(key, "x1011")){ if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);} else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} - sysPrefs->forceCacheWrite(); + //sysPrefs->forceCacheWrite(); + } else if (!strcmp(key, "x1012")){ + if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);} + else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} + //sysPrefs->forceCacheWrite(); + } else if (!strcmp(key, "x1020")){ + if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);} + else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} + sysPrefs->forceCacheWrite(); } else if (!strcmp(key, "x1040")){ if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);} else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} - sysPrefs->forceCacheWrite(); + // sysPrefs->forceCacheWrite(); + } else if (!strcmp(key, "x1050")){ + if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);} + else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} + // sysPrefs->forceCacheWrite(); } else if (!strcmp(key, "x2000")){ if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);} else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} - sysPrefs->forceCacheWrite(); + sysPrefs->forceCacheWrite(); + } else if (!strcmp(key, "x4400")){ + if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);} + else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} + // sysPrefs->forceCacheWrite(); + sysPrefs->forceCacheWrite(); } else if (!strcmp(key, "x6000")){ if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);} else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} - sysPrefs->forceCacheWrite(); - } else if (!strcmp(key, "x6500")){ + // sysPrefs->forceCacheWrite(); + } else if (!strcmp(key, "x650")){ if (255==atol(value)){sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), true);} else {sysPrefs->setDeviceStatus(strtol(key+1, 0, 16), false);} - sysPrefs->forceCacheWrite(); + // sysPrefs->forceCacheWrite(); } else if (!strcmp(key, Constants::logLevel)) { extern PrefHandler *sysPrefs; @@ -850,6 +866,10 @@ void ICHIPWIFI::processParameterChange(char *key) { Logger::info(ICHIP2128, "parameter change: %s", key); getNextParam(); // try to get another one immediately } + else { + sysPrefs->forceCacheWrite(); + DeviceManager::getInstance()->updateWifi(); + } } /* @@ -865,6 +885,8 @@ void ICHIPWIFI::loadParameters() { MotorControllerConfiguration *motorConfig = NULL; Logger::info("loading config params to ichip/wifi"); + + //DeviceManager::getInstance()->updateWifi(); if (accelerator) acceleratorConfig = (PotThrottleConfiguration *)accelerator->getConfiguration(); @@ -940,3 +962,5 @@ void ICHIPWIFI::saveConfiguration() { // prefsHandler->write(EESYS_WIFI0_SSID, config->ssid); // prefsHandler->saveChecksum(); } + + diff --git a/ichip_2128.h b/ichip_2128.h index c5d768e..739724c 100644 --- a/ichip_2128.h +++ b/ichip_2128.h @@ -203,3 +203,5 @@ class ICHIPWIFI : public Device { }; #endif + + diff --git a/sys_io.cpp b/sys_io.cpp index 00487f7..1345e68 100644 --- a/sys_io.cpp +++ b/sys_io.cpp @@ -392,3 +392,5 @@ void sys_io_adc_poll() { } + + diff --git a/sys_io.h b/sys_io.h index ad6f296..a585cad 100644 --- a/sys_io.h +++ b/sys_io.h @@ -54,3 +54,5 @@ void sys_early_setup(); #endif + + diff --git a/util/BBESAB0801.IMF b/util/BBESAB0801.IMF old mode 100644 new mode 100755 diff --git a/util/MultiSerial/MultiSerial.ino b/util/MultiSerial/MultiSerial.ino old mode 100644 new mode 100755 diff --git a/util/connectTOap/connectTOap.ino b/util/connectTOap/connectTOap.ino old mode 100644 new mode 100755 diff --git a/util/connectasAP/connectasAP.ino b/util/connectasAP/connectasAP.ino old mode 100644 new mode 100755 diff --git a/util/connectsetup/connectsetup.ino b/util/connectsetup/connectsetup.ino old mode 100644 new mode 100755 diff --git a/util/i2128d810d35BCOM.IMF b/util/i2128d810d35BCOM.IMF old mode 100644 new mode 100755 diff --git a/util/i2128d810d35BCOM.IMZ b/util/i2128d810d35BCOM.IMZ old mode 100644 new mode 100755 diff --git a/website/src/about.htm b/website/src/about.htm old mode 100644 new mode 100755 index 63df815..fa1799d --- a/website/src/about.htm +++ b/website/src/about.htm @@ -1,4 +1,4 @@ -

ABOUT GEVCU 5.200

+

ABOUT GEVCU 5.220

diff --git a/website/src/devices.htm b/website/src/devices.htm old mode 100644 new mode 100755 index 3d5ea39..e286bcd --- a/website/src/devices.htm +++ b/website/src/devices.htm @@ -75,47 +75,39 @@ - Brusa NLG Charger - - + ELM327 OBDII Wireless - - TCCH/Elcon Charger - + - OBDII PID Listener - - Lear Charger - - + - - - THINK Systems BMS - + + +
diff --git a/website/src/devices.xml b/website/src/devices.xml old mode 100644 new mode 100755 index 52e12ea..06501f5 --- a/website/src/devices.xml +++ b/website/src/devices.xml @@ -9,9 +9,13 @@ ~x1033~ ~x1034~ ~x1040~ - ~x6500~ + ~x1050~ + ~x650~ + ~x6000~ + ~x4400~ ~x1010~ - ~x1020~ + ~x1011~ + ~x1012~ ~x2000~ \ No newline at end of file diff --git a/website/src/index.htm b/website/src/index.htm index 34a80bd..6200438 100755 --- a/website/src/index.htm +++ b/website/src/index.htm @@ -1,7 +1,8 @@ - GEVCU 5.200 + + GEVCU 5.220 @@ -13,25 +14,31 @@ loadPage("status"); loadPage("dashboard"); loadPage("config"); + showTab("status"); loadPage("outputs"); loadPage("inputs"); loadPage("devices"); loadPage("about"); - showTab('status'); - } + loadPage("outputs"); + loadPage("inputs"); + loadPage("devices"); + loadPage("about"); + } + + -

GEVCU 5.200

- +

GEVCU 5.220

diff --git a/website/src/inputs.htm b/website/src/inputs.htm old mode 100644 new mode 100755 diff --git a/website/src/inputs.xml b/website/src/inputs.xml old mode 100644 new mode 100755 diff --git a/website/src/outputs.htm b/website/src/outputs.htm old mode 100644 new mode 100755 diff --git a/website/src/outputs.xml b/website/src/outputs.xml old mode 100644 new mode 100755 diff --git a/website/website.img b/website/website.img index 1f9bb80..be35174 100755 Binary files a/website/website.img and b/website/website.img differ