示例#1
0
/*
 * Get parameters from devices and forward them to ichip.
 * This is required to initially set-up the
 */
void ICHIPWIFI::loadParameters() {
	MotorController *motorController = DeviceManager::getInstance()->getMotorController();
	Throttle *accelerator = DeviceManager::getInstance()->getAccelerator();
	Throttle *brake = DeviceManager::getInstance()->getBrake();
	PotThrottleConfiguration *acceleratorConfig = NULL;
	PotThrottleConfiguration *brakeConfig = NULL;
	MotorControllerConfiguration *motorConfig = NULL;

	Logger::info("loading config params to ichip/wifi");

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

	if (acceleratorConfig) {
		setParam("numThrottlePots", acceleratorConfig->numberPotMeters);
		setParam("throttleSubType", acceleratorConfig->throttleSubType);
		setParam("throttleMin1", acceleratorConfig->minimumLevel1);
		setParam("throttleMin2", acceleratorConfig->minimumLevel2);
		setParam("throttleMax1", acceleratorConfig->maximumLevel1);
		setParam("throttleMax2", acceleratorConfig->maximumLevel2);
		setParam("throttleRegenMax", (uint16_t)(acceleratorConfig->positionRegenMaximum / 10));
		setParam("throttleRegenMin", (uint16_t)(acceleratorConfig->positionRegenMinimum / 10));
		setParam("throttleFwd", (uint16_t)(acceleratorConfig->positionForwardMotionStart / 10));
		setParam("throttleMap", (uint16_t)(acceleratorConfig->positionHalfPower / 10));
		setParam("throttleMinRegen", acceleratorConfig->minimumRegen);
		setParam("throttleMaxRegen", acceleratorConfig->maximumRegen);
		setParam("throttleCreep", acceleratorConfig->creep);
	}
	if (brakeConfig) {
		setParam("brakeMin", brakeConfig->minimumLevel1);
		setParam("brakeMax", brakeConfig->maximumLevel1);
		setParam("brakeMinRegen", brakeConfig->minimumRegen);
		setParam("brakeMaxRegen", brakeConfig->maximumRegen);
	}
	if (motorConfig) {
		setParam("speedMax", motorConfig->speedMax);
		setParam("torqueMax", (uint16_t)(motorConfig->torqueMax / 10)); // skip the tenth's
	}
}
示例#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
}
示例#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
/*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);
}
示例#5
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();
    }
}
示例#6
0
/*
 * Get parameters from devices and forward them to ichip.
 * This is required to initially set-up the ichip
 */
void ADAFRUITBLE::loadParameters() {
    MotorController *motorController = DeviceManager::getInstance()->getMotorController();
    Throttle *accelerator = DeviceManager::getInstance()->getAccelerator();
    Throttle *brake = DeviceManager::getInstance()->getBrake();
    PotThrottleConfiguration *acceleratorConfig = NULL;
    PotThrottleConfiguration *brakeConfig = NULL;
    MotorControllerConfiguration *motorConfig = NULL;

    Logger::info("loading config params to adafruit ble");

    //DeviceManager::getInstance()->updateWifi();

    if (accelerator)
        acceleratorConfig = (PotThrottleConfiguration *)accelerator->getConfiguration();
    if (brake)
        brakeConfig = (PotThrottleConfiguration *)brake->getConfiguration();
    if (motorController)
        motorConfig = (MotorControllerConfiguration *)motorController->getConfiguration();    
    
    if (acceleratorConfig) {
        bleThrottleIO.numThrottlePots = acceleratorConfig->numberPotMeters;
        bleThrottleIO.throttleType = acceleratorConfig->throttleSubType;
        bleThrottleIO.throttle1Min = acceleratorConfig->minimumLevel1;
        bleThrottleIO.throttle2Min = acceleratorConfig->minimumLevel2;
        bleThrottleIO.throttle1Max = acceleratorConfig->maximumLevel1;
        bleThrottleIO.throttle2Max = acceleratorConfig->maximumLevel2;
        bleThrottleIO.doUpdate = 1;
        bleThrottleMap.throttleRegenMax = acceleratorConfig->positionRegenMaximum;
        bleThrottleMap.throttleRegenMin = acceleratorConfig->positionRegenMinimum;
        bleThrottleMap.throttleFwd = acceleratorConfig->positionForwardMotionStart;
        bleThrottleMap.throttleMap = acceleratorConfig->positionHalfPower;
        bleThrottleMap.throttleLowestRegen = acceleratorConfig->minimumRegen;
        bleThrottleMap.throttleHighestRegen = acceleratorConfig->maximumRegen;
        bleThrottleMap.throttleCreep = acceleratorConfig->creep;
        bleThrottleMap.doUpdate = 1;
    }
    if (brakeConfig) {
        bleBrakeParam.brakeMin = brakeConfig->minimumLevel1;
        bleBrakeParam.brakeMax = brakeConfig->maximumLevel1;
        bleBrakeParam.brakeRegenMin = brakeConfig->minimumRegen;
        bleBrakeParam.brakeRegenMax = brakeConfig->maximumRegen;
        bleBrakeParam.doUpdate = 1;
    }
    if (motorConfig) {
        bleDigIO.coolingRelay = motorConfig->coolFan;
        bleDigIO.coolOnTemp = motorConfig->coolOn;
        bleDigIO.coolOffTemp = motorConfig->coolOff;
        bleDigIO.brakeLightOut = motorConfig->brakeLight;
        bleDigIO.reverseLightOut = motorConfig->revLight;
        bleDigIO.enableIn = motorConfig->enableIn;
        bleDigIO.reverseIn = motorConfig->reverseIn;
        bleDigIO.prechargeDuration = motorConfig->prechargeR;
        bleDigIO.prechargeRelay = motorConfig->prechargeRelay;
        bleDigIO.mainContRelay = motorConfig->mainContactorRelay;
        bleDigIO.doUpdate = 1;
        bleMaxParams.nomVoltage = motorConfig->nominalVolt;
        bleMaxParams.maxTorque = motorConfig->torqueMax;
        bleMaxParams.maxRPM = motorConfig->speedMax;
        bleMaxParams.doUpdate = 1;
    }
    bleModes.logLevel = (uint8_t)Logger::getLogLevel();
    bleModes.doUpdate = 1;
    
    transferUpdates();
}