int main(int argc, char* argv[]) { MotorController motorController; motorController.connect("\\\\.\\COM10", CBR_115200); ImageProcessor imageProcessor(motorController); //motorController.setUltraSonicSensor("\\\\.\\COM17", CBR_9600); //motorController.initializeUltraSonicSensor(); Application::EnableVisualStyles(); Application::SetCompatibleTextRenderingDefault(false); TennisBallCollection::RobotControlUI form(motorController, imageProcessor); Application::Run(%form); /* MotorController mC; mC.start("\\\\.\\COM17"); ImageProcessor ip(mC); ip.process(); */ return 0; }
int main(int argc, char **argv) { ros::init(argc, argv, "motor_controller"); MotorController controller; controller.init(); //----COMMENT OUT ONE FUNCTION TO GET PARAMETERS ----- // GET KP,KI,KD from launch file controller.GetTuningParameters(); //GET Ku,Tu to calculate KP,KI,KD (Ziegler-Nihcols) //controller.GetZieglerNichlosParam(); // --------------------------------------------------- // This calls a linear velocity and angular velocity from launch file //controller.GetVelocities(); ros::Rate loop_rate(10); while (controller.n.ok()) { ros::spinOnce(); controller.controllerVelocities(); loop_rate.sleep(); } return 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 } }
void Heartbeat::handleTick() { // Print a dot if no other output has been made since the last tick if (Logger::getLastLogTime() < lastTickTime) { SerialUSB.print('.'); if ((++dotCount % 80) == 0) { SerialUSB.println(); } } lastTickTime = millis(); if (led) { digitalWrite(BLINK_LED, HIGH); } else { digitalWrite(BLINK_LED, LOW); } led = !led; if (throttleDebug) { MotorController *motorController = DeviceManager::getInstance()->getMotorController(); Throttle *accelerator = DeviceManager::getInstance()->getAccelerator(); Throttle *brake = DeviceManager::getInstance()->getBrake(); Logger::console(""); if (motorController) { Logger::console("Motor Controller Status: isRunning: %T isFaulted: %T", motorController->isRunning(), motorController->isFaulted()); } Logger::console("AIN0: %d, AIN1: %d, AIN2: %d, AIN3: %d", getAnalog(0), getAnalog(1), getAnalog(2), getAnalog(3)); Logger::console("DIN0: %d, DIN1: %d, DIN2: %d, DIN3: %d", getDigital(0), getDigital(1), getDigital(2), getDigital(3)); Logger::console("DOUT0: %d, DOUT1: %d, DOUT2: %d, DOUT3: %d,DOUT4: %d, DOUT5: %d, DOUT6: %d, DOUT7: %d", getOutput(0), getOutput(1), getOutput(2), getOutput(3),getOutput(4), getOutput(5), getOutput(6), getOutput(7)); if (accelerator) { Logger::console("Throttle Status: isFaulted: %T level: %i", accelerator->isFaulted(), accelerator->getLevel()); RawSignalData *rawSignal = accelerator->acquireRawSignal(); Logger::console("Throttle rawSignal1: %d, rawSignal2: %d", rawSignal->input1, rawSignal->input2); } if (brake) { Logger::console("Brake Output: %i", brake->getLevel()); RawSignalData *rawSignal = brake->acquireRawSignal(); Logger::console("Brake rawSignal1: %d", rawSignal->input1); } } }
int main(int argc, char **argv) { /* initialize ros usage */ ros::init(argc, argv, "motor_controller"); /* parameters */ std::string motor_power_pub_topic; std::string navigation_speed_sub_topic; std::string wii_speed_sub_topic; std::string warhorse_state_topic; std::string left_odometry_sub_topic; std::string right_odometry_sub_topic; double max_speed, p_left, i_left, d_left, p_right, i_right, d_right, max_acceleration, max_deacceleration, windup_left, windup_right; /* private nodehandlers */ ros::NodeHandle nh; ros::NodeHandle n("~"); /* read parameters from ros parameter server if available otherwise use default values */ n.param<std::string> ("motor_power_topic", motor_power_pub_topic, "motor_power"); //Specify the publisher name n.param<std::string> ("navigation_speed_subscriber_topic", navigation_speed_sub_topic, "/navigation_vel"); //Specify the publisher name n.param<std::string> ("wii_speed_subscriber_topic", wii_speed_sub_topic, "/fmHMI/wii_vel_cmd"); //Specify the publisher name n.param<std::string> ("warhorse_state_topic", warhorse_state_topic, "/state"); //Specify the publisher name n.param<std::string> ("left_odo_subscriber_topic", left_odometry_sub_topic, "/fmSensors/left_odometry"); //Specify the publisher name n.param<std::string> ("right_odo_subscriber_topic", right_odometry_sub_topic, "/fmSensors/right_odometry"); //Specify the publisher name n.param<double> ("maximum_speed", max_speed, 1); //Specify the maximum speed in m/s n.param<double> ("maximum_acceleration", max_acceleration, 0); //Specify the maximum acceleration in m/s² (0 = inf acceleration) n.param<double> ("maximum_deacceleration", max_deacceleration, 0); //Specify the maximum deacceleration in m/s² (0 = inf deacceleration) n.param<double> ("p_left", p_left, 1); n.param<double> ("i_left", i_left, 0); n.param<double> ("d_left", d_left, 0); n.param<double> ("p_right", p_right, 1); n.param<double> ("i_right", i_right, 0); n.param<double> ("d_right", d_right, 0); n.param<double> ("windup_left", windup_left, 1000); n.param<double> ("windup_right", windup_right, 1000); MotorController mc = MotorController(p_left,i_left,d_left,p_right,i_right,d_right); mc.setMaxSpeed(max_speed); mc.setMaxAcceleration(max_acceleration); mc.setMaxDeacceleration(max_deacceleration); mc.setIWindupLimitLeft(windup_left); mc.setIWindupLimitRight(windup_right); mc.navigation_speed_sub = n.subscribe<geometry_msgs::TwistStamped>(navigation_speed_sub_topic.c_str(),1,&MotorController::navigationSpeedHandler,&mc); mc.wii_speed_sub = n.subscribe<geometry_msgs::TwistStamped>(wii_speed_sub_topic.c_str(),1,&MotorController::wiiSpeedHandler,&mc); mc.warhorse_state_sub = n.subscribe<fmMsgs::warhorse_state>(warhorse_state_topic.c_str(),1,&MotorController::stateHandler,&mc); mc.left_odo_sub = n.subscribe(left_odometry_sub_topic.c_str(), 1, &MotorController::leftMotorHandler,&mc); mc.right_odo_sub = n.subscribe(right_odometry_sub_topic.c_str(), 1, &MotorController::rightMotorHandler,&mc); mc.motor_power_pub = n.advertise<fmMsgs::motor_power>(motor_power_pub_topic.c_str(), 1); ros::spin(); // wait for callbacks return 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--; } } }
/* * 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 }
//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; }
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."); } }
/*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); }
INT MotorControllerTestApplication::Main() { Trace0Enter(""); MotorController M; M.Initialize(m_DeviceName, m_BaudRate); StdOut.WriteLine("Commands are:"); StdOut.WriteLine("EXIT"); StdOut.WriteLine("QUIT"); StdOut.WriteLine("STOP [LEFT|RIGHT]"); StdOut.WriteLine("LEFT <Speed>"); StdOut.WriteLine("RIGHT <Speed>"); StdOut.WriteLine("DRIVE <Speed>"); StdOut.WriteLine("TURN <Speed>"); while (TRUE) { StdOut.Write((LPCTSTR) "Current Speed: %f / %f\n>", M.GetSpeed(0), M.GetSpeed(1) ); String Command = StdIn.ReadLine(); Command.ToUpper(); Array<String> Commands = Command.Split(String::IsWhitespace); if (Commands.Length() < 1) continue; if (Commands[0] == "EXIT" || Commands[0] == "QUIT") break; if (Commands[0] == "HELP") { StdOut.WriteLine("Commands are:"); StdOut.WriteLine("EXIT"); StdOut.WriteLine("QUIT"); StdOut.WriteLine("STOP [LEFT|RIGHT]"); StdOut.WriteLine("LEFT <Speed>"); StdOut.WriteLine("RIGHT <Speed>"); StdOut.WriteLine("DRIVE <Speed>"); StdOut.WriteLine("TURN <Speed>"); } if (Commands[0] == "STOP") { if (Commands.Length() == 1) { M.Stop(); } else { if (Commands[1] == "LEFT") M.SetTrackSpeed(0,0); if (Commands[1] == "RIGHT") M.SetTrackSpeed(1,0); } } if (Commands[0] == "DRIVE") { FLOAT Speed = Parse<FLOAT>(Commands[1]); M.SetTrackSpeed(0, Speed); M.SetTrackSpeed(1, Speed); } if (Commands[0] == "LEFT") { FLOAT Speed = Parse<FLOAT>(Commands[1]); M.SetTrackSpeed(0, Speed); } if (Commands[0] == "RIGHT") { FLOAT Speed = Parse<FLOAT>(Commands[1]); M.SetTrackSpeed(1, Speed); } if (Commands[0] == "TURN") { FLOAT Speed = Parse<FLOAT>(Commands[1]); M.SetTrackSpeed(0, -Speed); M.SetTrackSpeed(1, +Speed); } } M.Stop(); return 0; }
// DEFINE : MAIN LOOP >> int main(int argc, char ** argv) { // SETUP : ROS >> ros::init(argc, argv, "ground_node"); ros::NodeHandle nh; // SETUP : Rotary Encoder >> int en0_ticks = -1; int en1_ticks = -1; // SETUP : Rotary Encoders >> GPIO_IN en0_pin(30, "both", 0); GPIO_IN en1_pin(60, "both", 0); en0_pin.epoll_setup(); en1_pin.epoll_setup(); // SETUP : Motor Controller & Service Server >> // GPIO_31, GPIO_48, pwmchip2, 2000Hz MotorController* mc = new MotorController(31, 48, 2, PERIOD); ServiceController* sc = new ServiceController(&nh); ros::ServiceServer service = nh.advertiseService("ground/set", &ServiceController::callback, sc); // SETUP : Threads >> thread spin_thread(spin_td); thread ticks0_thread(ticks_td, &en0_pin, &en0_ticks, &mc->dir[0]); thread ticks1_thread(ticks_td, &en1_pin, &en1_ticks, &mc->dir[1]); // SETUP : Loop Variables >> int error, kp, loop_freq; int spd_0, spd_1; int t0_old, t0_new; int t1_old, t1_new; int ticks_speedup[5]; SpeedCalc spd_calc; // SETUP : ROS Parameters >> ros::param::param<int>("~error", error, 0); ros::param::param<int>("~kp", kp, 500); ros::param::param<int>("~loop_freq", loop_freq, 10); ROS_INFO( "Set Parameters : error[%d], kp[%d], loop_freq[%d]", error, kp, loop_freq ); // SETUP : Waiters >> ros::Rate waiter(10); // 10Hz = 0.1s ros::Rate mode0_waiter(loop_freq); // 10Hz = 0.1s // SETUP : Binder >> auto move_to_pos = std::bind( move_to_pos_raw, sc, mc, placeholders::_2, &spd_0, &spd_1, &error, &kp, &t0_old, &t0_new, &t1_old, &t1_new, &en0_ticks, &en1_ticks, placeholders::_1, placeholders::_3 ); // LOOP : Main Algorithm >>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>>> while (ros::ok()) { // Wait for new service call : while (ros::ok() && !sc->is_new()) {waiter.sleep();} ROS_INFO("Request Recieved : OK"); sc->set_incomplete(); mc->stop(); // Reset Variables : en0_ticks = en1_ticks = 0; /* for encoder */ error = t0_old = t0_new = t1_old = t1_new = 0; /* for feedback */ // Begin Movement : switch (sc->mode) { case '0': // MODE '0' : No Speedup or Speeddown >>>>>>>>>>>>>>>>>>>>>>>>>>>>> spd_0 = spd_1 = PERIOD * sc->speed/100; if (move_to_pos(sc->distance, &mode0_waiter, -1)) { sc->set_complete(); } break; case '1': // MODE '1' : Set Speedup & Speeddown with duration 2s >>>>>>>>>>>> // Initialise speeds : spd_calc.init(PERIOD * 1/2, PERIOD * sc->speed/100, 3); // Speedup section : spd_0 = spd_1 = spd_calc.get(0); if (move_to_pos(sc->distance, &mode0_waiter, 0.7)) {sc->set_complete(); break;} ticks_speedup[0] = (en0_ticks + en1_ticks)/2; ROS_INFO("Request Processing : TICKS[%d, %d]", en0_ticks, en1_ticks); spd_0 = spd_1 = spd_calc.get(1); if (move_to_pos(sc->distance, &mode0_waiter, 0.7)) {sc->set_complete(); break;} ticks_speedup[1] = (en0_ticks + en1_ticks)/2; ROS_INFO("Request Processing : TICKS[%d, %d]", en0_ticks, en1_ticks); spd_0 = spd_1 = spd_calc.get(2); if (move_to_pos(sc->distance, &mode0_waiter, 0.7)) {sc->set_complete(); break;} ticks_speedup[2] = (en0_ticks + en1_ticks)/2; ROS_INFO("Request Processing : TICKS[%d, %d]", en0_ticks, en1_ticks); // Max speed section : spd_0 = spd_1 = spd_calc.get(3); if (move_to_pos(sc->distance - ticks_speedup[2], &mode0_waiter, -1.0)) {sc->set_complete();} ROS_INFO("Request Processing : TICKS[%d, %d]", en0_ticks, en1_ticks); // Speeddown section : spd_0 = spd_1 = spd_calc.get(2); if (move_to_pos(sc->distance - ticks_speedup[1], &mode0_waiter, 0.7)) {sc->set_complete();} ROS_INFO("Request Processing : TICKS[%d, %d]", en0_ticks, en1_ticks); spd_0 = spd_1 = spd_calc.get(1); if (move_to_pos(sc->distance - ticks_speedup[0], &mode0_waiter, 0.7)) {sc->set_complete();} ROS_INFO("Request Processing : TICKS[%d, %d]", en0_ticks, en1_ticks); spd_0 = spd_1 = spd_calc.get(0); if (move_to_pos(sc->distance, &mode0_waiter, 1)) {sc->set_complete();} ROS_INFO("Request Completed : TICKS[%d, %d]", en0_ticks, en1_ticks); break; } // Complete Service : mc->stop(); ROS_INFO("Request Ended : TICKS[%d, %d]", en0_ticks, en1_ticks); } // CLOSURE >> spin_thread.join(); ticks0_thread.join(); ticks1_thread.join(); delete sc, mc; return 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(); } }
//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*)¶mCache.timeRunning, 4)) { Logger::error("Could not update timeRunning"); } else Logger::debug(ADABLUE, "Updated timeRunning"); dumpRawData((uint8_t *)¶mCache.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 }
/* * 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(); }