示例#1
0
/*
 * Periodic updates of parameters to ichip RAM.
 * Also query for changed parameters of the config page.
 */
void ICHIPWIFI::handleTick() {
	MotorController* motorController = DeviceManager::getInstance()->getMotorController();
	Throttle *accelerator = DeviceManager::getInstance()->getAccelerator();
	Throttle *brake = DeviceManager::getInstance()->getBrake();

	tickCounter++;

	// make small slices so the main loop is not blocked for too long
	if (tickCounter == 1) {
		if (motorController) {
			setParam("timeRunning", getTimeRunning());
			setParam("torqueRequested", motorController->getTorqueRequested() / 10.0f, 1);
			setParam("torqueActual", motorController->getTorqueActual() / 10.0f, 1);
		}
		if (accelerator)
			setParam("throttle", accelerator->getLevel() / 10.0f, 1);
		if (brake)
			setParam("brake", brake->getLevel() / 10.0f, 1);
		else
			setParam("brake", "n/a");
	} else if (tickCounter == 2) {
		if (motorController) {
			setParam("speedRequested", motorController->getSpeedRequested());
			setParam("speedActual", motorController->getSpeedActual());
			setParam("dcVoltage", motorController->getDcVoltage() / 10.0f, 1);
			setParam("dcCurrent", motorController->getDcCurrent() / 10.0f, 1);
		}
	} else if (tickCounter == 3) {
		if (motorController) {
			setParam("acCurrent", motorController->getAcCurrent() / 10.0f, 1);
			setParam("bitfield1", motorController->getStatusBitfield1());
			setParam("bitfield2", motorController->getStatusBitfield2());
			setParam("bitfield3", motorController->getStatusBitfield3());
			setParam("bitfield4", motorController->getStatusBitfield4());
		}
	} else if (tickCounter == 4) {
		if (motorController) {
			setParam("running", (motorController->isRunning() ? "true" : "false"));
			setParam("faulted", (motorController->isFaulted() ? "true" : "false"));
			setParam("warning", (motorController->isWarning() ? "true" : "false"));
			setParam("gear", (uint16_t) motorController->getGearSwitch());
		}
	} else if (tickCounter > 4) {
		if (motorController) {
			setParam("tempMotor", motorController->getTemperatureMotor() / 10.0f, 1);
			setParam("tempInverter", motorController->getTemperatureInverter() / 10.0f, 1);
			setParam("tempSystem", motorController->getTemperatureSystem() / 10.0f, 1);
			setParam("mechPower", motorController->getMechanicalPower() / 10.0f, 1);
			tickCounter = 0;
		}
		getNextParam();

		// wait "loadParams" cycles of tickCounter > 4 before sending config parameters
		// sending them too early after a soft-reset of ichip results in lost data.
		if (loadParams > 0) {
			if (loadParams == 1)
				loadParameters();
			loadParams--;
		}
	}
}
示例#2
0
void Heartbeat::handleTick() {
	// Print a dot if no other output has been made since the last tick
	if (Logger::getLastLogTime() < lastTickTime) {
		SerialUSB.print('.');
		if ((++dotCount % 80) == 0) {
			SerialUSB.println();
		}
	}
	lastTickTime = millis();

	if (led) {
		digitalWrite(BLINK_LED, HIGH);
	} else {
		digitalWrite(BLINK_LED, LOW);
	}
	led = !led;

	if (throttleDebug) {
		MotorController *motorController = DeviceManager::getInstance()->getMotorController();
		Throttle *accelerator = DeviceManager::getInstance()->getAccelerator();
		Throttle *brake = DeviceManager::getInstance()->getBrake();

		Logger::console("");
		if (motorController) {
			Logger::console("Motor Controller Status: isRunning: %T isFaulted: %T", motorController->isRunning(), motorController->isFaulted());
		}

		Logger::console("AIN0: %d, AIN1: %d, AIN2: %d, AIN3: %d", getAnalog(0), getAnalog(1), getAnalog(2), getAnalog(3));
        Logger::console("DIN0: %d, DIN1: %d, DIN2: %d, DIN3: %d", getDigital(0), getDigital(1), getDigital(2), getDigital(3));
        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));

		if (accelerator) {
			Logger::console("Throttle Status: isFaulted: %T level: %i", accelerator->isFaulted(), accelerator->getLevel());
			RawSignalData *rawSignal = accelerator->acquireRawSignal();
			Logger::console("Throttle rawSignal1: %d, rawSignal2: %d", rawSignal->input1, rawSignal->input2);
		}
		if (brake) {
			Logger::console("Brake Output: %i", brake->getLevel());
			RawSignalData *rawSignal = brake->acquireRawSignal();
			Logger::console("Brake rawSignal1: %d", rawSignal->input1);
		}
	}
}
示例#3
0
void SerialConsole::printMenu() {
	MotorController* motorController = (MotorController*) DeviceManager::getInstance()->getMotorController();
	Throttle *accelerator = DeviceManager::getInstance()->getAccelerator();
	Throttle *brake = DeviceManager::getInstance()->getBrake();
	ICHIPWIFI *wifi = (ICHIPWIFI*) DeviceManager::getInstance()->getDeviceByType(DEVICE_WIFI);

	//Show build # here as well in case people are using the native port and don't get to see the start up messages
	SerialUSB.print("Build number: ");
	SerialUSB.println(CFG_BUILD_NUM);
	if (motorController) {
		SerialUSB.println(
			"Motor Controller Status: isRunning: " + String(motorController->isRunning()) + " isFaulted: " + String(motorController->isFaulted()));
	}
	SerialUSB.println("System Menu:");
	SerialUSB.println();
	SerialUSB.println("Enable line endings of some sort (LF, CR, CRLF)");
	SerialUSB.println();
	SerialUSB.println("Short Commands:");
	SerialUSB.println("h = help (displays this message)");
	if (heartbeat != NULL) {
		SerialUSB.println("L = show raw analog/digital input/output values (toggle)");
	}
	SerialUSB.println("K = set all outputs high");
	SerialUSB.println("J = set all outputs low");
	//SerialUSB.println("U,I = test EEPROM routines");
	SerialUSB.println("E = dump system eeprom values");
	SerialUSB.println("z = detect throttle min/max, num throttles and subtype");
	SerialUSB.println("Z = save throttle values");
	SerialUSB.println("b = detect brake min/max");
	SerialUSB.println("B = save brake values");
	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("s = Scan WiFi for nearby access points");
	SerialUSB.println();
	SerialUSB.println("Config Commands (enter command=newvalue). Current values shown in parenthesis:");
    SerialUSB.println();
    Logger::console("LOGLEVEL=%i - set log level (0=debug, 1=info, 2=warn, 3=error, 4=off)", Logger::getLogLevel());
   
	uint8_t systype;
	sysPrefs->read(EESYS_SYSTEM_TYPE, &systype);
	Logger::console("SYSTYPE=%i - Set board revision (Dued=2, GEVCU3=3, GEVCU4=4)", systype);

	DeviceManager::getInstance()->printDeviceList();

	if (motorController && motorController->getConfiguration()) {
		MotorControllerConfiguration *config = (MotorControllerConfiguration *) motorController->getConfiguration();
                  
         SerialUSB.println();
         SerialUSB.println("MOTOR CONTROLS");
         SerialUSB.println();
		Logger::console("TORQ=%i - Set torque upper limit (tenths of a Nm)", config->torqueMax);
		Logger::console("RPM=%i - Set maximum RPM", config->speedMax);
		Logger::console("REVLIM=%i - How much torque to allow in reverse (Tenths of a percent)", config->reversePercent);
                            
	        Logger::console("COOLFAN=%i - Digital output to turn on cooling fan(0-7, 255 for none)", config->coolFan);
                Logger::console("COOLON=%i - Inverter temperature C to turn cooling on", config->coolOn);
                Logger::console("COOLOFF=%i - Inverter temperature C to turn cooling off", config->coolOff);  
                Logger::console("BRAKELT = %i - Digital output to turn on brakelight (0-7, 255 for none)", config->brakeLight);
                Logger::console("REVLT=%i - Digital output to turn on reverse light (0-7, 255 for none)", config->revLight);
                Logger::console("ENABLEIN=%i - Digital input to enable motor controller (0-3, 255 for none)", config->enableIn);
                Logger::console("REVIN=%i - Digital input to reverse motor rotation (0-3, 255 for none)", config->reverseIn);
       
	}


	if (accelerator && accelerator->getConfiguration()) {
		PotThrottleConfiguration *config = (PotThrottleConfiguration *) accelerator->getConfiguration();
         SerialUSB.println();
         SerialUSB.println("THROTTLE CONTROLS");
         SerialUSB.println();
	
		Logger::console("TPOT=%i - Number of pots to use (1 or 2)", config->numberPotMeters);
		Logger::console("TTYPE=%i - Set throttle subtype (1=std linear, 2=inverse)", config->throttleSubType);
		Logger::console("T1ADC=%i - Set throttle 1 ADC pin", config->AdcPin1);
		Logger::console("T1MN=%i - Set throttle 1 min value", config->minimumLevel1);
		Logger::console("T1MX=%i - Set throttle 1 max value", config->maximumLevel1);
		Logger::console("T2ADC=%i - Set throttle 2 ADC pin", config->AdcPin2);
		Logger::console("T2MN=%i - Set throttle 2 min value", config->minimumLevel2);
		Logger::console("T2MX=%i - Set throttle 2 max value", config->maximumLevel2);
		Logger::console("TRGNMAX=%i - Tenths of a percent of pedal where regen is at max", config->positionRegenMaximum);
		Logger::console("TRGNMIN=%i - Tenths of a percent of pedal where regen is at min", config->positionRegenMinimum);
		Logger::console("TFWD=%i - Tenths of a percent of pedal where forward motion starts", config->positionForwardMotionStart);
		Logger::console("TMAP=%i - Tenths of a percent of pedal where 50% throttle will be", config->positionHalfPower);
		Logger::console("TMINRN=%i - Percent of full torque to use for min throttle regen", config->minimumRegen);
		Logger::console("TMAXRN=%i - Percent of full torque to use for max throttle regen", config->maximumRegen);
		Logger::console("TCREEP=%i - Percent of full torque to use for creep (0=disable)", config->creep);
	}

	if (brake && brake->getConfiguration()) {
		PotThrottleConfiguration *config = (PotThrottleConfiguration *) brake->getConfiguration();
                SerialUSB.println();
                SerialUSB.println("BRAKE CONTROLS");
	        SerialUSB.println();

		Logger::console("B1ADC=%i - Set brake ADC pin", config->AdcPin1);
		Logger::console("B1MN=%i - Set brake min value", config->minimumLevel1);
		Logger::console("B1MX=%i - Set brake max value", config->maximumLevel1);
		Logger::console("BMINR=%i - Percent of full torque for start of brake regen", config->minimumRegen);
		Logger::console("BMAXR=%i - Percent of full torque for maximum brake regen", config->maximumRegen);
	}

	if (motorController && motorController->getConfiguration()) {
		MotorControllerConfiguration *config = (MotorControllerConfiguration *) motorController->getConfiguration();
                SerialUSB.println();
                SerialUSB.println("PRECHARGE CONTROLS");
	        SerialUSB.println();

		Logger::console("PREDELAY=%i - Precharge delay time in milliseconds ", config->prechargeR);
	        Logger::console("PRELAY=%i - Which output to use for precharge contactor (255 to disable)", config->prechargeRelay);
		Logger::console("MRELAY=%i - Which output to use for main contactor (255 to disable)", config->mainContactorRelay);
                SerialUSB.println();
                SerialUSB.println("WIRELESS LAN COMMANDS");
	        SerialUSB.println();
                Logger::console("WIREACH=anycommand - sends ATi+anycommand to WiReach Module");
                Logger::console("SSID=anyname - sets broadcast ID to anyname");
                Logger::console("IP=192.168.3.10 - sets IP of website to whatever IP is entered");
                Logger::console("PWD=secret - sets website configuration password to entered string");
                Logger::console("CHANNEL=4 - sets website wireless channel - 1 to 11");
                Logger::console("SECURITY=password - sets website wireless connection security for WPA2-AES and password");
             
                SerialUSB.println();
                SerialUSB.println("OTHER");
	        SerialUSB.println();

		Logger::console("NOMV=%i - Fully charged pack voltage that automatically resets kWh counter", config->nominalVolt/10);
                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.");
             
	}

	
}
示例#4
0
//TODO: See the processing function below for a more detailed explanation - can't send so many setParam commands in a row
void ADAFRUITBLE::handleTick() {
    MotorController* motorController = DeviceManager::getInstance()->getMotorController();
    Throttle *accelerator = DeviceManager::getInstance()->getAccelerator();
    Throttle *brake = DeviceManager::getInstance()->getBrake();
    BatteryManager *bms = reinterpret_cast<BatteryManager *>(DeviceManager::getInstance()->getDeviceByType(DEVICE_BMS));
    
    uint32_t ms = millis();
    uint32_t IOTemp = 0;
    uint8_t brklt;
    tickCounter++;

    if (ms < 1000) return; //wait 1 seconds for things to settle before doing a thing

    // Do a delayed parameter load once about a second after startup
    if (!didParamLoad && ms > 5000) {
        loadParameters();
        Logger::console("BLE characteristics loaded...");
        bleBitFields.bitfield1 = motorController->getStatusBitfield1();
        bleBitFields.bitfield2 = motorController->getStatusBitfield2();
        bleBitFields.doUpdate = 1;        
        // DeviceManager::getInstance()->updateWifiByID(BRUSA_DMC5);
        didParamLoad = true;
    }
    
    if (paramCache.timeRunning != (ms / 1000))
    {
        paramCache.timeRunning = ms / 1000;
        if (!gatt.setChar(MeasureCharId[0], (uint8_t*)&paramCache.timeRunning, 4))
        {
            Logger::error("Could not update timeRunning");
        }
        else Logger::debug(ADABLUE, "Updated timeRunning");
        dumpRawData((uint8_t *)&paramCache.timeRunning, 4);
    }
    
    //every other time - 80ms by default
    if (tickCounter & 1)
    {
        if (motorController) {
            if ( bleTrqReqAct.torqueRequested  != motorController->getTorqueRequested() ) {
                bleTrqReqAct.torqueRequested = motorController->getTorqueRequested();
                bleTrqReqAct.doUpdate = 1;
            }
            if ( bleTrqReqAct.torqueActual != motorController->getTorqueActual() ) {
                bleTrqReqAct.torqueActual = motorController->getTorqueActual();
                bleTrqReqAct.doUpdate = 1;
            }
            if ( bleSpeeds.speedRequested != motorController->getSpeedRequested() ) {
                bleSpeeds.speedRequested = motorController->getSpeedRequested();
                bleSpeeds.doUpdate = 1;
            }
            
            if ( bleSpeeds.speedActual != motorController->getSpeedActual() ) {
                bleSpeeds.speedActual = motorController->getSpeedActual();
                bleSpeeds.doUpdate = 1;
            }
        }
    
        if (accelerator) {
            RawSignalData *rawSignal = accelerator->acquireRawSignal();
            if ( bleThrBrkLevels.throttleRawLevel1 !=  rawSignal->input1) 
            {
                bleThrBrkLevels.throttleRawLevel1 = rawSignal->input1;
                bleThrBrkLevels.doUpdate = 1;
            }
            if ( bleThrBrkLevels.throttleRawLevel2 !=  rawSignal->input2) 
            {
                bleThrBrkLevels.throttleRawLevel2 = rawSignal->input2;
                bleThrBrkLevels.doUpdate = 1;
            }
            if (bleThrBrkLevels.throttlePercentage != accelerator->getLevel() / 10)
            {
                bleThrBrkLevels.throttlePercentage = accelerator->getLevel() / 10;
                bleThrBrkLevels.doUpdate = 1;
            }
        }
        if (brake) {
            RawSignalData *rawSignal = brake->acquireRawSignal();
            if (bleThrBrkLevels.brakeRawLevel !=  rawSignal->input1) {
                bleThrBrkLevels.brakeRawLevel = rawSignal->input1;
                paramCache.brakeNotAvailable = false;
                bleThrBrkLevels.doUpdate = 1;
            }
            if (bleThrBrkLevels.brakePercentage !=  brake->getLevel() / 10) {
                bleThrBrkLevels.brakePercentage = brake->getLevel() / 10;
                bleThrBrkLevels.doUpdate = 1;
            }            
        } else {
            if ( paramCache.brakeNotAvailable == true ) {
                paramCache.brakeNotAvailable = false; // no need to keep sending this
                bleThrBrkLevels.brakeRawLevel = 0;
                bleThrBrkLevels.doUpdate = 1;
            }
        }
    }
    
    if (tickCounter == 2) {
        if (bms)
        {
            if (blePowerStatus.SOC != bms->getSOC())
            {
                blePowerStatus.SOC = bms->getSOC();
                blePowerStatus.doUpdate = 1;
            }
        }
        if (motorController) {
            //Logger::console("Wifi tick counter 2...");            
            if ( blePowerStatus.busVoltage != motorController->getDcVoltage() ) {
                blePowerStatus.busVoltage = motorController->getDcVoltage();
                if(blePowerStatus.busVoltage<0) blePowerStatus.busVoltage=0; 
                //if(blePowerStatus.busVoltage>4500) blePowerStatus.busVoltage=4500;
                blePowerStatus.doUpdate = 1;
            }
            
            if ( blePowerStatus.busCurrent != motorController->getDcCurrent() ) {
                blePowerStatus.busCurrent = motorController->getDcCurrent();
                blePowerStatus.doUpdate = 1;
            }
            
            if ( blePowerStatus.motorCurrent != motorController->getAcCurrent() ) {
                blePowerStatus.motorCurrent = motorController->getAcCurrent();
                blePowerStatus.doUpdate = 1;
            }

            if ( blePowerStatus.kwHours != motorController->getKiloWattHours()/3600000 ) {
                blePowerStatus.kwHours = motorController->getKiloWattHours()/3600000;
                if(blePowerStatus.kwHours<0)blePowerStatus.kwHours = 0;
                if(blePowerStatus.kwHours>300)blePowerStatus.kwHours = 300;
                blePowerStatus.doUpdate = 1;
            }
            
            if ( blePowerStatus.mechPower != motorController->getMechanicalPower() ) {
                blePowerStatus.mechPower = motorController->getMechanicalPower();
                if (blePowerStatus.mechPower<-250)blePowerStatus.mechPower=-250;
                if (blePowerStatus.mechPower>1500)blePowerStatus.mechPower=1500;
                blePowerStatus.doUpdate = 1;
            }

            //DeviceManager::getInstance()->updateWifi();
        }
    } else if (tickCounter == 3) {
        if (motorController) {
            //Logger::console("Wifi tick counter 3...");

            if ( bleMaxParams.nomVoltage != motorController->getnominalVolt() ) {
                bleMaxParams.nomVoltage = motorController->getnominalVolt();
                bleMaxParams.doUpdate = 1;
            }

            if ( bleBitFields.bitfield1 != motorController->getStatusBitfield1() ) {
                bleBitFields.bitfield1 = motorController->getStatusBitfield1();
                bleBitFields.doUpdate = 1;
            }
            if ( bleBitFields.bitfield2 != motorController->getStatusBitfield2() ) {
                bleBitFields.bitfield2 = motorController->getStatusBitfield2();
                bleBitFields.doUpdate = 1;
            }
            
            IOTemp = 0;
            for (int i = 0; i < 4; i++)
            {
                if (getDigital(i)) bleBitFields.digitalInputs |= 1 << i;
            }            
                        
            if ( bleBitFields.digitalInputs != IOTemp ) {
                bleBitFields.digitalInputs = IOTemp;
                bleBitFields.doUpdate = 1;
            }
            
            IOTemp = 0;
            for (int i = 0; i < 8; i++)
            {
                if (getOutput(i)) bleBitFields.digitalOutputs |= 1 << i;
            }
            
            if ( bleBitFields.digitalOutputs != IOTemp ) {
                bleBitFields.digitalOutputs = IOTemp;
                bleBitFields.doUpdate = 1;
            }
            
            if ( bleModes.isRunning != motorController->isRunning() ) {
                bleModes.isRunning = motorController->isRunning();
                bleModes.doUpdate = 1;
            }
            if ( bleModes.isFaulted != motorController->isFaulted() ) {
                bleModes.isFaulted = motorController->isFaulted();
                bleModes.doUpdate = 1;
            }
            if ( bleModes.isWarning != motorController->isWarning() ) {
                bleModes.isWarning = motorController->isWarning();
                bleModes.doUpdate = 1;
            }
            if ( bleModes.gear != motorController->getSelectedGear() ) {
                bleModes.gear = motorController->getSelectedGear();
                bleModes.doUpdate = 1;
            }
            
            if ( bleModes.powerMode != motorController->getPowerMode() ) {
                bleModes.powerMode = motorController->getPowerMode();
                bleModes.doUpdate = 1;
            }

        }
    } else if (tickCounter == 4) {
        if (motorController) {
            //Logger::console("Wifi tick counter 4...");
            
            if ( bleDigIO.prechargeDuration != motorController->getprechargeR() ) {
                bleDigIO.prechargeDuration = motorController->getprechargeR();
                bleDigIO.doUpdate = 1;
            }

            if ( bleDigIO.prechargeRelay != motorController->getprechargeRelay() ) {
                bleDigIO.prechargeRelay = motorController->getprechargeRelay();
                bleDigIO.doUpdate = 1;
                //Logger::console("Precharge Relay %i", paramCache.prechargeRelay);
                //Logger::console("motorController:prechargeRelay:%d, paramCache.prechargeRelay:%d, Constants:prechargeRelay:%s", motorController->getprechargeRelay(),paramCache.prechargeRelay, Constants::prechargeRelay);
            }

            if ( bleDigIO.mainContRelay != motorController->getmainContactorRelay() ) {
                bleDigIO.mainContRelay = motorController->getmainContactorRelay();
                bleDigIO.doUpdate = 1;
            }


            if ( bleDigIO.coolingRelay != motorController->getCoolFan() ) {
                bleDigIO.coolingRelay = motorController->getCoolFan();
                bleDigIO.doUpdate = 1;
            }

            if ( bleDigIO.coolOnTemp != motorController->getCoolOn() ) {
                bleDigIO.coolOnTemp = motorController->getCoolOn();
                bleDigIO.doUpdate = 1;
            }

            if ( bleDigIO.coolOffTemp != motorController->getCoolOff() ) {
                bleDigIO.coolOffTemp = motorController->getCoolOff();
                bleDigIO.doUpdate = 1;
            }

            if ( bleDigIO.brakeLightOut != motorController->getBrakeLight() ) {
                bleDigIO.brakeLightOut = motorController->getBrakeLight();
                bleDigIO.doUpdate = 1;
            }

            if ( bleDigIO.reverseLightOut != motorController->getRevLight() ) {
                bleDigIO.reverseLightOut = motorController->getRevLight();
                bleDigIO.doUpdate = 1;
            }

            if ( bleDigIO.enableIn != motorController->getEnableIn() ) {
                bleDigIO.enableIn = motorController->getEnableIn();
                bleDigIO.doUpdate = 1;
            }
            if ( bleDigIO.reverseIn != motorController->getReverseIn() ) {
                bleDigIO.reverseIn = motorController->getReverseIn();
                bleDigIO.doUpdate = 1;
            }
        }
    } else if (tickCounter > 4) {
        if (motorController) {
            //Logger::console("Wifi tick counter 5...");
            if ( bleTemperatures.motorTemperature != motorController->getTemperatureMotor() ) {
                bleTemperatures.motorTemperature = motorController->getTemperatureMotor();
                bleTemperatures.doUpdate = 1;
            }
            if ( bleTemperatures.inverterTemperature != motorController->getTemperatureInverter() ) {
                bleTemperatures.inverterTemperature = motorController->getTemperatureInverter();
                bleTemperatures.doUpdate = 1;
            }
            if ( bleTemperatures.systemTemperature != motorController->getTemperatureSystem() ) {
                bleTemperatures.systemTemperature = motorController->getTemperatureSystem();
                bleTemperatures.doUpdate = 1;
            }

        }
        tickCounter = 0;
    }
    transferUpdates(); //send out any updates required
}