Exemplo n.º 1
0
/*For simplicity the configuration setting code uses four characters for each configuration choice. This makes things easier for
 comparison purposes.
 */
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 newValue;
	bool updateWifi = true;

	//Logger::debug("Cmd size: %i", ptrBuffer);
	if (ptrBuffer < 6)
		return; //4 digit command, =, value is at least 6 characters
	cmdBuffer[ptrBuffer] = 0; //make sure to null terminate
	String cmdString = String();
	unsigned char whichEntry = '0';
	i = 0;

	while (cmdBuffer[i] != '=' && i < ptrBuffer) {
	 cmdString.concat(String(cmdBuffer[i++]));
	}
	i++; //skip the =
	if (i >= ptrBuffer)
	{
		Logger::console("Command needs a value..ie TORQ=3000");
		Logger::console("");
		return; //or, we could use this to display the parameter instead of setting
	}

	if (accelerator)
		acceleratorConfig = (PotThrottleConfiguration *) accelerator->getConfiguration();
	if (brake)
		brakeConfig = (PotThrottleConfiguration *) brake->getConfiguration();
	if (motorController)
		motorConfig = (MotorControllerConfiguration *) motorController->getConfiguration();

	// strtol() is able to parse also hex values (e.g. a string "0xCAFE"), useful for enable/disable by device id
	newValue = strtol((char *) (cmdBuffer + i), NULL, 0);

	cmdString.toUpperCase();
	if (cmdString == String("TORQ") && motorConfig) {
		Logger::console("Setting Torque Limit to %i", newValue);
		motorConfig->torqueMax = newValue;
		motorController->saveConfiguration();
	} else if (cmdString == String("RPM") && motorConfig) {
		Logger::console("Setting RPM Limit to %i", newValue);
		motorConfig->speedMax = newValue;
		motorController->saveConfiguration();
	} else if (cmdString == String("REVLIM") && motorConfig) {
		Logger::console("Setting Reverse Limit to %i", newValue);
		motorConfig->reversePercent = newValue;
		motorController->saveConfiguration();
	} else if (cmdString == String("TPOT") && acceleratorConfig) {
		Logger::console("Setting # of Throttle Pots to %i", newValue);
		acceleratorConfig->numberPotMeters = newValue;
		accelerator->saveConfiguration();
	} else if (cmdString == String("TTYPE") && acceleratorConfig) {
		Logger::console("Setting Throttle Subtype to %i", newValue);
		acceleratorConfig->throttleSubType = newValue;
		accelerator->saveConfiguration();
	} else if (cmdString == String("T1ADC") && acceleratorConfig) {
		Logger::console("Setting Throttle1 ADC pin to %i", newValue);
		acceleratorConfig->AdcPin1 = newValue;
		accelerator->saveConfiguration();
	} else if (cmdString == String("T1MN") && acceleratorConfig) {
		Logger::console("Setting Throttle1 Min to %i", newValue);
		acceleratorConfig->minimumLevel1 = newValue;
		accelerator->saveConfiguration();
	} else if (cmdString == String("T1MX") && acceleratorConfig) {
		Logger::console("Setting Throttle1 Max to %i", newValue);
		acceleratorConfig->maximumLevel1 = newValue;
		accelerator->saveConfiguration();
	}
	else if (cmdString == String("T2ADC") && acceleratorConfig) {
		Logger::console("Setting Throttle2 ADC pin to %i", newValue);
		acceleratorConfig->AdcPin2 = newValue;
		accelerator->saveConfiguration();
	} else if (cmdString == String("T2MN") && acceleratorConfig) {
		Logger::console("Setting Throttle2 Min to %i", newValue);
		acceleratorConfig->minimumLevel2 = newValue;
		accelerator->saveConfiguration();
	} else if (cmdString == String("T2MX") && acceleratorConfig) {
		Logger::console("Setting Throttle2 Max to %i", newValue);
		acceleratorConfig->maximumLevel2 = newValue;
		accelerator->saveConfiguration();
	} else if (cmdString == String("TRGNMAX") && acceleratorConfig) {
		Logger::console("Setting Throttle Regen maximum to %i", newValue);
		acceleratorConfig->positionRegenMaximum = newValue;
		accelerator->saveConfiguration();
	} else if (cmdString == String("TRGNMIN") && acceleratorConfig) {
		Logger::console("Setting Throttle Regen minimum to %i", newValue);
		acceleratorConfig->positionRegenMinimum = newValue;
		accelerator->saveConfiguration();
	} else if (cmdString == String("TFWD") && acceleratorConfig) {
		Logger::console("Setting Throttle Forward Start to %i", newValue);
		acceleratorConfig->positionForwardMotionStart = newValue;
		accelerator->saveConfiguration();
	} else if (cmdString == String("TMAP") && acceleratorConfig) {
		Logger::console("Setting Throttle MAP Point to %i", newValue);
		acceleratorConfig->positionHalfPower = newValue;
		accelerator->saveConfiguration();
	} else if (cmdString == String("TMINRN") && acceleratorConfig) {
		Logger::console("Setting Throttle Regen Minimum Strength to %i", newValue);
		acceleratorConfig->minimumRegen = newValue;
		accelerator->saveConfiguration();
	} else if (cmdString == String("TMAXRN") && acceleratorConfig) {
		Logger::console("Setting Throttle Regen Maximum Strength to %i", newValue);
		acceleratorConfig->maximumRegen = newValue;
		accelerator->saveConfiguration();
	} else if (cmdString == String("TCREEP") && acceleratorConfig) {
		Logger::console("Setting Throttle Creep Strength to %i", newValue);
		acceleratorConfig->creep = newValue;
		accelerator->saveConfiguration();
	} else if (cmdString == String("BMAXR") && brakeConfig) {
		Logger::console("Setting Max Brake Regen to %i", newValue);
		brakeConfig->maximumRegen = newValue;
		brake->saveConfiguration();
	} else if (cmdString == String("BMINR") && brakeConfig) {
		Logger::console("Setting Min Brake Regen to %i", newValue);
		brakeConfig->minimumRegen = newValue;
		brake->saveConfiguration();
	}
	else if (cmdString == String("B1ADC") && acceleratorConfig) {
		Logger::console("Setting Brake ADC pin to %i", newValue);
		brakeConfig->AdcPin1 = newValue;
		accelerator->saveConfiguration();
	} else if (cmdString == String("B1MX") && brakeConfig) {
		Logger::console("Setting Brake Max to %i", newValue);
		brakeConfig->maximumLevel1 = newValue;
		brake->saveConfiguration();
	} else if (cmdString == String("B1MN") && brakeConfig) {
		Logger::console("Setting Brake Min to %i", newValue);
		brakeConfig->minimumLevel1 = newValue;
		brake->saveConfiguration();
	} else if (cmdString == String("PREC") && motorConfig) {
		Logger::console("Setting Precharge Capacitance to %i", newValue);
		motorConfig->kilowattHrs = newValue;
		motorController->saveConfiguration();
	} else if (cmdString == String("PREDELAY") && motorConfig) {
		Logger::console("Setting Precharge Time Delay to %i milliseconds", newValue);
		motorConfig->prechargeR = newValue;
		motorController->saveConfiguration();
	} else if (cmdString == String("NOMV") && motorConfig) {
		Logger::console("Setting fully charged voltage to %d vdc", newValue);
		motorConfig->nominalVolt = newValue * 10;
		motorController->saveConfiguration();
        } else if (cmdString == String("BRAKELT") && motorConfig) {
		motorConfig->brakeLight = newValue;
		motorController->saveConfiguration();
		Logger::console("Brake light output set to DOUT%i.",newValue);
 } else if (cmdString == String("REVLT") && motorConfig) {
		motorConfig->revLight = newValue;
		motorController->saveConfiguration();
		Logger::console("Reverse light output set to DOUT%i.",newValue);
 } else if (cmdString == String("ENABLEIN") && motorConfig) {
		motorConfig->enableIn = newValue;
		motorController->saveConfiguration();
		Logger::console("Motor Enable input set to DIN%i.",newValue);
 } else if (cmdString == String("REVIN") && motorConfig) {
		motorConfig->reverseIn = newValue;
		motorController->saveConfiguration();
		Logger::console("Motor Reverse input set to DIN%i.",newValue);
	} else if (cmdString == String("MRELAY") && motorConfig) {
		Logger::console("Setting Main Contactor relay output to DOUT%i", newValue);
		motorConfig->mainContactorRelay = newValue;
		motorController->saveConfiguration();
	} else if (cmdString == String("PRELAY") && motorConfig) {
		Logger::console("Setting Precharge Relay output to DOUT%i", newValue);
		motorConfig->prechargeRelay = newValue;
		motorController->saveConfiguration();
	} else if (cmdString == String("ENABLE")) {
		if (PrefHandler::setDeviceStatus(newValue, true)) {
			sysPrefs->forceCacheWrite(); //just in case someone takes us literally and power cycles quickly
			Logger::console("Successfully enabled device.(%X, %d) Power cycle to activate.", newValue, newValue);
		}
		else {
			Logger::console("Invalid device ID (%X, %d)", newValue, newValue);
		}
	} else if (cmdString == String("DISABLE")) {
		if (PrefHandler::setDeviceStatus(newValue, false)) {
			sysPrefs->forceCacheWrite(); //just in case someone takes us literally and power cycles quickly
			Logger::console("Successfully disabled device. Power cycle to deactivate.");
		}
		else {
			Logger::console("Invalid device ID (%X, %d)", newValue, newValue);
		}
	} else if (cmdString == String("SYSTYPE")) {
		if (newValue < 5 && newValue > 0) {
			sysPrefs->write(EESYS_SYSTEM_TYPE, (uint8_t)(newValue));
			sysPrefs->saveChecksum();
			sysPrefs->forceCacheWrite(); //just in case someone takes us literally and power cycles quickly
			Logger::console("System type updated. Power cycle to apply.");
		}
		else Logger::console("Invalid system type. Please enter a value 1 - 4");

       
	} else if (cmdString == String("LOGLEVEL")) {
		switch (newValue) {
		case 0:
			Logger::setLoglevel(Logger::Debug);
			Logger::console("setting loglevel to 'debug'");
			break;
		case 1:
			Logger::setLoglevel(Logger::Info);
			Logger::console("setting loglevel to 'info'");
			break;
		case 2:
			Logger::console("setting loglevel to 'warning'");
			Logger::setLoglevel(Logger::Warn);
			break;
		case 3:
			Logger::console("setting loglevel to 'error'");
			Logger::setLoglevel(Logger::Error);
			break;
		case 4:
			Logger::console("setting loglevel to 'off'");
			Logger::setLoglevel(Logger::Off);
			break;
		}
		sysPrefs->write(EESYS_LOG_LEVEL, (uint8_t)newValue);
		sysPrefs->saveChecksum();

	} else if (cmdString == String("WIREACH")) {
		DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)(cmdBuffer + i));
		Logger::info("sent \"AT+i%s\" to WiReach wireless LAN device", (cmdBuffer + i));
                DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DOWN");	
		updateWifi = false;
	} else if (cmdString == String("SSID")) {
		String cmdString = String();
    	        cmdString.concat("WLSI");
   		cmdString.concat('=');
		cmdString.concat((char *)(cmdBuffer + i));
                Logger::info("Sent \"%s\" to WiReach wireless LAN device", (cmdString.c_str()));
       		DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)cmdString.c_str());
                DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DOWN");	
		updateWifi = false;
        } else if (cmdString == String("IP")) {
		String cmdString = String();
    	        cmdString.concat("DIP");
   		cmdString.concat('=');
		cmdString.concat((char *)(cmdBuffer + i));
                Logger::info("Sent \"%s\" to WiReach wireless LAN device", (cmdString.c_str()));
       		DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)cmdString.c_str());
                DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DOWN");	
		updateWifi = false;
 } else if (cmdString == String("CHANNEL")) {
		String cmdString = String();
    	        cmdString.concat("WLCH");
   		cmdString.concat('=');
		cmdString.concat((char *)(cmdBuffer + i));
                Logger::info("Sent \"%s\" to WiReach wireless LAN device", (cmdString.c_str()));
       		DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)cmdString.c_str());
                DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DOWN");	
		updateWifi = false;
	} else if (cmdString == String("SECURITY")) {
		String cmdString = String();
    	        cmdString.concat("WLPP");
   		cmdString.concat('=');
		cmdString.concat((char *)(cmdBuffer + i));
                Logger::info("Sent \"%s\" to WiReach wireless LAN device", (cmdString.c_str()));
       		DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)cmdString.c_str());
                DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DOWN");	
		updateWifi = false;
	
   } else if (cmdString == String("PWD")) {
		String cmdString = String();
    	        cmdString.concat("WPWD");
   		cmdString.concat('=');
		cmdString.concat((char *)(cmdBuffer + i));
                Logger::info("Sent \"%s\" to WiReach wireless LAN device", (cmdString.c_str()));
       		DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)cmdString.c_str());
                DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_COMMAND, (void *)"DOWN");	
		updateWifi = false;
	
	} else if (cmdString == String("COOLFAN") && motorConfig) {		
		Logger::console("Cooling fan output updated to: %i", newValue);
        motorConfig->coolFan = newValue;
		motorController->saveConfiguration();
	} else if (cmdString == String("COOLON")&& motorConfig) {
		if (newValue <= 200 && newValue >= 0) {
			Logger::console("Cooling fan ON temperature updated to: %i degrees", newValue);
			motorConfig->coolOn = newValue;
			motorController->saveConfiguration();
		}
		else Logger::console("Invalid cooling ON temperature. Please enter a value 0 - 200F");
	} else if (cmdString == String("COOLOFF")&& motorConfig) {
		if (newValue <= 200 && newValue >= 0) {
			Logger::console("Cooling fan OFF temperature updated to: %i degrees", newValue);
			motorConfig->coolOff = newValue;
			motorController->saveConfiguration();
	    }
		else Logger::console("Invalid cooling OFF temperature. Please enter a value 0 - 200F");
	} else if (cmdString == String("OUTPUT") && newValue<8) {
                int outie = getOutput(newValue);
                Logger::console("DOUT%d,  STATE: %d",newValue, outie);
                if(outie)
                  {
                    setOutput(newValue,0);
                    motorController->statusBitfield1 &= ~(1 << newValue);//Clear
                  }
                   else
                     {
                       setOutput(newValue,1);
                        motorController->statusBitfield1 |=1 << newValue;//setbit to Turn on annunciator
		      }
                  
             
        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")) {
		if (newValue == 1) 
		{   //write zero to the checksum location of every device in the table.
			//Logger::console("Start of EEPROM Nuke");
			uint8_t zeroVal = 0;
			for (int j = 0; j < 64; j++) 
			{
				memCache->Write(EE_DEVICES_BASE + (EE_DEVICE_SIZE * j), zeroVal);
				memCache->FlushAllPages();
			}			
			Logger::console("Device settings have been nuked. Reboot to reload default settings");
		}
	} else {
		Logger::console("Unknown command");
		updateWifi = false;
	}
	// send updates to ichip wifi
	if (updateWifi)
		DeviceManager::getInstance()->sendMessage(DEVICE_WIFI, ICHIP2128, MSG_CONFIG_CHANGE, NULL);
}
Exemplo n.º 2
0
/*
 * Process the parameter update from ichip we received as a response to AT+iWNXT.
 * The response usually looks like this : key="value", so the key can be isolated
 * by looking for the '=' sign and the leading/trailing '"' have to be ignored.
 */
void ICHIPWIFI::processParameterChange(char *key) {
	PotThrottleConfiguration *acceleratorConfig = NULL;
	PotThrottleConfiguration *brakeConfig = NULL;
	MotorControllerConfiguration *motorConfig = NULL;
	Throttle *accelerator = DeviceManager::getInstance()->getAccelerator();
	Throttle *brake = DeviceManager::getInstance()->getBrake();
	MotorController *motorController = DeviceManager::getInstance()->getMotorController();

	if (accelerator)
		acceleratorConfig = (PotThrottleConfiguration *)accelerator->getConfiguration();
	if (brake)
		brakeConfig = (PotThrottleConfiguration *)brake->getConfiguration();
	if(motorController)
		motorConfig = (MotorControllerConfiguration *)motorController->getConfiguration();

	char *value = strchr(key, '=');
	if (value) {
		value[0] = 0; // replace the '=' sign with a 0
		value++;
		if (value[0] == '"')
			value++; // if the value starts with a '"', advance one character
		if (value[strlen(value) - 1] == '"')
			value[strlen(value) - 1] = 0; // if the value ends with a '"' character, replace it with 0

		if (!strcmp(key, "numThrottlePots") && acceleratorConfig) {
			acceleratorConfig->numberPotMeters = atol(value);
			accelerator->saveConfiguration();
		} else if (!strcmp(key, "throttleSubType") && acceleratorConfig) {
			acceleratorConfig->throttleSubType = atol(value);
			accelerator->saveConfiguration();
		} else if (!strcmp(key, "throttleMin1") && acceleratorConfig) {
			acceleratorConfig->minimumLevel1 = atol(value);
			accelerator->saveConfiguration();
		} else if (!strcmp(key, "throttleMin2") && acceleratorConfig) {
			acceleratorConfig->minimumLevel2 = atol(value);
			accelerator->saveConfiguration();
		} else if (!strcmp(key, "throttleMax1") && acceleratorConfig) {
			acceleratorConfig->maximumLevel1 = atol(value);
			accelerator->saveConfiguration();
		} else if (!strcmp(key, "throttleMax2") && acceleratorConfig) {
			acceleratorConfig->maximumLevel2 = atol(value);
			accelerator->saveConfiguration();
		} else if (!strcmp(key, "throttleRegenMax") && acceleratorConfig) {
			acceleratorConfig->positionRegenMaximum = atol(value) * 10;
		} else if (!strcmp(key, "throttleRegenMin") && acceleratorConfig) {
			acceleratorConfig->positionRegenMinimum = atol(value) * 10;
			accelerator->saveConfiguration();
		} else if (!strcmp(key, "throttleFwd") && acceleratorConfig) {
			acceleratorConfig->positionForwardMotionStart = atol(value) * 10;
			accelerator->saveConfiguration();
		} else if (!strcmp(key, "throttleMap") && acceleratorConfig) {
			acceleratorConfig->positionHalfPower = atol(value) * 10;
			accelerator->saveConfiguration();
		} else if (!strcmp(key, "throttleMinRegen") && acceleratorConfig) {
			acceleratorConfig->minimumRegen = atol(value);
			accelerator->saveConfiguration();
		} else if (!strcmp(key, "throttleMaxRegen") && acceleratorConfig) {
			acceleratorConfig->maximumRegen = atol(value);
			accelerator->saveConfiguration();
		} else if (!strcmp(key, "throttleCreep") && acceleratorConfig) {
			acceleratorConfig->creep = atol(value);
			accelerator->saveConfiguration();
		} else if (!strcmp(key, "brakeMin") && brakeConfig) {
			brakeConfig->minimumLevel1 = atol(value);
			brake->saveConfiguration();
		} else if (!strcmp(key, "brakeMax") && brakeConfig) {
			brakeConfig->maximumLevel1 = atol(value);
			brake->saveConfiguration();
		} else if (!strcmp(key, "brakeMinRegen") && brakeConfig) {
			brakeConfig->minimumRegen = atol(value);
			brake->saveConfiguration();
		} else if (!strcmp(key, "brakeMaxRegen") && brakeConfig) {
			brakeConfig->maximumRegen = atol(value);
			brake->saveConfiguration();
		} else if (!strcmp(key, "speedMax") && motorConfig) {
			motorConfig->speedMax = atol(value);
			motorController->saveConfiguration();
		} else if (!strcmp(key, "torqueMax") && motorConfig) {
			motorConfig->torqueMax = atol(value) * 10;
			motorController->saveConfiguration();
		}
	}
	getNextParam(); // try to get another one immediately
}
Exemplo n.º 3
0
/*
 * Process the parameter update from ichip we received as a response to AT+iWNXT.
 * The response usually looks like this : key="value", so the key can be isolated
 * by looking for the '=' sign and the leading/trailing '"' have to be ignored.
 */
void ADAFRUITBLE::processParameterChange(char *key) {
    PotThrottleConfiguration *acceleratorConfig = NULL;
    PotThrottleConfiguration *brakeConfig = NULL;
    MotorControllerConfiguration *motorConfig = NULL;
    bool parameterFound = true;

    char *value = strchr(key, '=');
    if (!value)
        return;

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

    if (accelerator)
        acceleratorConfig = (PotThrottleConfiguration *)accelerator->getConfiguration();
    if (brake)
        brakeConfig = (PotThrottleConfiguration *)brake->getConfiguration();
    if(motorController)
        motorConfig = (MotorControllerConfiguration *)motorController->getConfiguration();

    value[0] = 0; // replace the '=' sign with a 0
    value++;
    if (value[0] == '"')
        value++; // if the value starts with a '"', advance one character
    if (value[strlen(value) - 1] == '"')
        value[strlen(value) - 1] = 0; // if the value ends with a '"' character, replace it with 0

    if (!strcmp(key, Constants::numThrottlePots) && acceleratorConfig) {
        acceleratorConfig->numberPotMeters = atol(value);
        accelerator->saveConfiguration();
    } else if (!strcmp(key, Constants::throttleSubType) && acceleratorConfig) {
        acceleratorConfig->throttleSubType = atol(value);
        accelerator->saveConfiguration();
    } else if (!strcmp(key, Constants::throttleMin1) && acceleratorConfig) {
        acceleratorConfig->minimumLevel1 = atol(value);
        accelerator->saveConfiguration();
    } else if (!strcmp(key, Constants::throttleMin2) && acceleratorConfig) {
        acceleratorConfig->minimumLevel2 = atol(value);
        accelerator->saveConfiguration();
    } else if (!strcmp(key, Constants::throttleMax1) && acceleratorConfig) {
        acceleratorConfig->maximumLevel1 = atol(value);
        accelerator->saveConfiguration();
    } else if (!strcmp(key, Constants::throttleMax2) && acceleratorConfig) {
        acceleratorConfig->maximumLevel2 = atol(value);
        accelerator->saveConfiguration();
    } else if (!strcmp(key, Constants::throttleRegenMax) && acceleratorConfig) {
        acceleratorConfig->positionRegenMaximum = atol(value) * 10;
    } else if (!strcmp(key, Constants::throttleRegenMin) && acceleratorConfig) {
        acceleratorConfig->positionRegenMinimum = atol(value) * 10;
        accelerator->saveConfiguration();
    } else if (!strcmp(key, Constants::throttleFwd) && acceleratorConfig) {
        acceleratorConfig->positionForwardMotionStart = atol(value) * 10;
        accelerator->saveConfiguration();
    } else if (!strcmp(key, Constants::throttleMap) && acceleratorConfig) {
        acceleratorConfig->positionHalfPower = atol(value) * 10;
        accelerator->saveConfiguration();
    } else if (!strcmp(key, Constants::throttleMinRegen) && acceleratorConfig) {
        acceleratorConfig->minimumRegen = atol(value);
        accelerator->saveConfiguration();
    } else if (!strcmp(key, Constants::throttleMaxRegen) && acceleratorConfig) {
        acceleratorConfig->maximumRegen = atol(value);
        accelerator->saveConfiguration();
    } else if (!strcmp(key, Constants::throttleCreep) && acceleratorConfig) {
        acceleratorConfig->creep = atol(value);
        accelerator->saveConfiguration();
    } else if (!strcmp(key, Constants::brakeMin) && brakeConfig) {
        brakeConfig->minimumLevel1 = atol(value);
        brake->saveConfiguration();
    } else if (!strcmp(key, Constants::brakeMax) && brakeConfig) {
        brakeConfig->maximumLevel1 = atol(value);
        brake->saveConfiguration();
    } else if (!strcmp(key, Constants::brakeMinRegen) && brakeConfig) {
        brakeConfig->minimumRegen = atol(value);
        brake->saveConfiguration();
    } else if (!strcmp(key, Constants::brakeMaxRegen) && brakeConfig) {
        brakeConfig->maximumRegen = atol(value);
        brake->saveConfiguration();
    } else if (!strcmp(key, Constants::speedMax) && motorConfig) {
        motorConfig->speedMax = atol(value);
        motorController->saveConfiguration();
    } else if (!strcmp(key, Constants::torqueMax) && motorConfig) {
        motorConfig->torqueMax = atol(value) * 10;
        motorController->saveConfiguration();
    } else if (!strcmp(key, Constants::coolFan) && motorConfig) {
        motorConfig->coolFan = atol(value);
        motorController->saveConfiguration();
    } else if (!strcmp(key, Constants::coolOn) && motorConfig) {
        motorConfig->coolOn = (atol(value));
        motorController->saveConfiguration();
    } else if (!strcmp(key, Constants::coolOff) && motorConfig) {
        motorConfig->coolOff = (atol(value));
        motorController->saveConfiguration();
    } else if (!strcmp(key, Constants::prechargeR) && motorConfig) {
        motorConfig->prechargeR = atol(value);
        motorController->saveConfiguration();
    } else if (!strcmp(key, Constants::prechargeRelay) && motorConfig) {
        motorConfig->prechargeRelay = atol(value);
        motorController->saveConfiguration();
    } else if (!strcmp(key, Constants::nominalVolt) && motorConfig) {
        motorConfig->nominalVolt = (atol(value))*10;
        motorController->saveConfiguration();

    } else if (!strcmp(key, Constants::mainContactorRelay) && motorConfig) {
        motorConfig->mainContactorRelay = atol(value);
        motorController->saveConfiguration();
    } else if (!strcmp(key, Constants::brakeLight) && motorConfig) {
        motorConfig->brakeLight = atol(value);
        motorController->saveConfiguration();
    } else if (!strcmp(key, Constants::revLight) && motorConfig) {
        motorConfig->revLight = atol(value);
        motorController->saveConfiguration();
    } else if (!strcmp(key, Constants::enableIn) && motorConfig) {
        motorConfig->enableIn = atol(value);
        motorController->saveConfiguration();
    } else if (!strcmp(key, Constants::reverseIn) && motorConfig) {
        motorConfig->reverseIn = atol(value);
        motorController->saveConfiguration();
        /*  } else if (!strcmp(key, Constants::motorMode) && motorConfig) {
        motorConfig->motorMode = (MotorController::PowerMode)atoi(value);
        motorController->saveConfiguration();
        */



    } 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();
    } 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();
    } 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();
    } 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();
    } 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();
    } 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();
    } 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();
    } 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, "x1011")) {
        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, "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();
    } 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();
    } 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, "x650")) {
        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, Constants::logLevel)) {
        extern PrefHandler *sysPrefs;
        uint8_t loglevel = atoi(value);
        Logger::setLoglevel((Logger::LogLevel)loglevel);
        sysPrefs->write(EESYS_LOG_LEVEL, loglevel);
    } else {
        parameterFound = false;
    }
    if (parameterFound) {
        Logger::info(ADABLUE, "parameter change: %s", key);
    }
    else {
        sysPrefs->forceCacheWrite();
        DeviceManager::getInstance()->updateWifi();
    }
}