Exemplo n.º 1
0
//Process SAE standard PID requests. Function returns whether it handled the request or not.
bool CanPIDListener::processShowData(CAN_FRAME* inFrame, CAN_FRAME& outFrame)
{
    MotorController* motorController = deviceManager.getMotorController();
    int temp;

    switch (inFrame->data.bytes[2]) {
        case 0: //pids 1-0x20 that we support - bitfield
            //returns 4 bytes so immediately indicate that.
            outFrame.data.bytes[0] += 4;
            outFrame.data.bytes[3] = 0b11011000; //pids 1 - 8 - starting with pid 1 in the MSB and going from there
            outFrame.data.bytes[4] = 0b00010000; //pids 9 - 0x10
            outFrame.data.bytes[5] = 0b10000000; //pids 0x11 - 0x18
            outFrame.data.bytes[6] = 0b00010011; //pids 0x19 - 0x20
            return true;
            break;

        case 1: //Returns 32 bits but we really can only support the first byte which has bit 7 = Malfunction? Bits 0-6 = # of DTCs
            outFrame.data.bytes[0] += 4;
            outFrame.data.bytes[3] = 0; //TODO: We aren't properly keeping track of faults yet but when we do fix this.
            outFrame.data.bytes[3] = 0; //these next three are really related to ICE diagnostics
            outFrame.data.bytes[3] = 0; //so ignore them.
            outFrame.data.bytes[3] = 0;
            return true;
            break;

        case 2: //Freeze DTC
            return false; //don't support freeze framing yet. Might be useful in the future.
            break;

        case 4: //Calculated engine load (A * 100 / 255) - Percentage
            temp = (255 * motorController->getTorqueActual()) / motorController->getTorqueAvailable();
            outFrame.data.bytes[0] += 1;
            outFrame.data.bytes[3] = (uint8_t)(temp & 0xFF);
            return true;
            break;

        case 5: //Engine Coolant Temp (A - 40) = Degrees Centigrade
            //our code stores temperatures as a signed integer for tenths of a degree so translate
            temp =  motorController->getTemperatureController() / 10;

            if (temp < -40) {
                temp = -40;
            }

            if (temp > 215) {
                temp = 215;
            }

            temp += 40;
            outFrame.data.bytes[0] += 1; //returning only one byte
            outFrame.data.bytes[3] = (uint8_t)(temp);
            return true;
            break;

        case 0xC: //Engine RPM (A * 256 + B) / 4
            temp = motorController->getSpeedActual() * 4; //we store in RPM while the PID code wants quarter rpms
            outFrame.data.bytes[0] += 2;
            outFrame.data.bytes[3] = (uint8_t)(temp / 256);
            outFrame.data.bytes[4] = (uint8_t)(temp);
            return true;
            break;

        case 0x11: //Throttle position (A * 100 / 255) - Percentage
            temp = motorController->getThrottleLevel() / 10; //getThrottle returns in 10ths of a percent

            if (temp < 0) {
                temp = 0;    //negative throttle can't be shown for OBDII
            }

            temp = (255 * temp) / 100;
            outFrame.data.bytes[0] += 1;
            outFrame.data.bytes[3] = (uint8_t)(temp);
            return true;
            break;

        case 0x1C: //Standard supported (We return 1 = OBDII)
            outFrame.data.bytes[0] += 1;
            outFrame.data.bytes[3] = 1;
            return true;
            break;

        case 0x1F: //runtime since engine start (A*256 + B)
            outFrame.data.bytes[0] += 2;
            outFrame.data.bytes[3] = 0; //TODO: Get the actual runtime.
            outFrame.data.bytes[4] = 0;
            return true;
            break;

        case 0x20: //pids supported (next 32 pids - formatted just like PID 0)
            outFrame.data.bytes[0] += 4;
            outFrame.data.bytes[3] = 0b00000000; //pids 0x21 - 0x28 - starting with pid 0x21 in the MSB and going from there
            outFrame.data.bytes[4] = 0b00000000; //pids 0x29 - 0x30
            outFrame.data.bytes[5] = 0b00000000; //pids 0x31 - 0x38
            outFrame.data.bytes[6] = 0b00000001; //pids 0x39 - 0x40
            return true;
            break;

        case 0x21: //Distance traveled with fault light lit (A*256 + B) - In km
            outFrame.data.bytes[0] += 2;
            outFrame.data.bytes[3] = 0; //TODO: Can we get this information?
            outFrame.data.bytes[4] = 0;
            return true;
            break;

        case 0x2F: //Fuel level (A * 100 / 255) - Percentage
            outFrame.data.bytes[0] += 1;
            outFrame.data.bytes[3] = 0; //TODO: finish BMS interface and get this value
            return true;
            break;

        case 0x40: //PIDs supported, next 32
            outFrame.data.bytes[0] += 4;
            outFrame.data.bytes[3] = 0b00000000; //pids 0x41 - 0x48 - starting with pid 0x41 in the MSB and going from there
            outFrame.data.bytes[4] = 0b00000000; //pids 0x49 - 0x50
            outFrame.data.bytes[5] = 0b10000000; //pids 0x51 - 0x58
            outFrame.data.bytes[6] = 0b00000001; //pids 0x59 - 0x60
            return true;
            break;

        case 0x51: //What type of fuel do we use? (We use 8 = electric, presumably.)
            outFrame.data.bytes[0] += 1;
            outFrame.data.bytes[3] = 8;
            return true;
            break;

        case 0x60: //PIDs supported, next 32
            outFrame.data.bytes[0] += 4;
            outFrame.data.bytes[3] = 0b11100000; //pids 0x61 - 0x68 - starting with pid 0x61 in the MSB and going from there
            outFrame.data.bytes[4] = 0b00000000; //pids 0x69 - 0x70
            outFrame.data.bytes[5] = 0b00000000; //pids 0x71 - 0x78
            outFrame.data.bytes[6] = 0b00000000; //pids 0x79 - 0x80
            return true;
            break;

        case 0x61: //Driver requested torque (A-125) - Percentage
            temp = (100 * motorController->getTorqueRequested()) / motorController->getTorqueAvailable();
            temp += 125;
            outFrame.data.bytes[0] += 1;
            outFrame.data.bytes[3] = (uint8_t) temp;
            return true;
            break;

        case 0x62: //Actual Torque delivered (A-125) - Percentage
            temp = (100 * motorController->getTorqueActual()) / motorController->getTorqueAvailable();
            temp += 125;
            outFrame.data.bytes[0] += 1;
            outFrame.data.bytes[3] = (uint8_t) temp;
            return true;
            break;

        case 0x63: //Reference torque for engine - presumably max torque - A*256 + B - Nm
            temp = motorController->getTorqueAvailable();
            outFrame.data.bytes[0] += 2;
            outFrame.data.bytes[3] = (uint8_t)(temp / 256);
            outFrame.data.bytes[4] = (uint8_t)(temp & 0xFF);
            return true;
            break;
    }

    return false;
}
Exemplo n.º 2
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--;
		}
	}
}
Exemplo n.º 3
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
}