diff --git a/controller/controller.ino b/controller/controller.ino index 282b1e9..3ff3bae 100644 --- a/controller/controller.ino +++ b/controller/controller.ino @@ -19,7 +19,10 @@ //#define MAXADCVALUE 4095 #define ADC_CALIB_THROTTLE_LOWEST 1900 //a bit above maximum adc value if throttle it not touched #define ADC_CALIB_THROTTLE_MIN 2000 //minimum adc value that should correspond to 0 speed -#define ADC_CALIB_THROTTLE_MAX 3120 //maximum adc value that should correspond to full speed +#define ADC_CALIB_THROTTLE_MAX 3110 //maximum adc value that should correspond to full speed + +#define ADC_CALIB_BRAKE_MIN 800 //minimum adc value that should correspond to 0 speed +#define ADC_CALIB_BRAKE_MAX 2400 //maximum adc value that should correspond to full speed #define PIN_STARTLED PA0 //Red LED inside Engine Start Button. Powered with 5V via transistor uint8_t startled=0; @@ -67,10 +70,15 @@ long state_modechange_time=0; long millis_lastadc=0; #define ADC_READTIME 10 //time interval to read adc (for filtering) -#define ADC_THROTTLE_FILTER 0.2 //low value = slower change +#define ADC_THROTTLE_FILTER 0.4 //low value = slower change +#define ADC_BRAKE_FILTER 0.4 //low value = slower change + int adc_throttle_raw=0; //raw throttle value from adc float adc_throttle=0; //filtered value +int adc_brake_raw=0; //raw throttle value from adc +float adc_brake=0; //filtered value + uint16_t out_speedFL=0; uint16_t out_speedFR=0; uint16_t out_speedRL=0; @@ -209,6 +217,7 @@ void loop() { ledUpdate(); modeloops(); + if (loopmillis - last_send > SENDPERIOD) { last_send=loopmillis; @@ -264,7 +273,11 @@ void handleInputs() if (loopmillis-millis_lastadc>ADC_READTIME) { adc_throttle_raw = analogRead(PIN_THROTTLE); adc_throttle = adc_throttle*(1-ADC_THROTTLE_FILTER) + adc_throttle_raw*ADC_THROTTLE_FILTER; - if (adc_throttle_raw >= ADC_CALIB_THROTTLE_MIN) { //throttle pressed + + adc_brake_raw = analogRead(PIN_BRAKE); + adc_brake = adc_brake*(1-ADC_BRAKE_FILTER) + adc_brake_raw*ADC_BRAKE_FILTER; + + if (adc_throttle_raw >= ADC_CALIB_THROTTLE_MIN || adc_brake_raw >= ADC_CALIB_BRAKE_MIN) { //throttle or brake pressed millis_lastchange=loopmillis; } millis_lastadc=loopmillis; @@ -276,8 +289,6 @@ void handleInputs() } void handleModeChange() { - - if (currentmode==requestmode) { //## Not currently changing modes ## switch (currentmode) { //mode dependant case booting: //on startup. active while start button is still pressed @@ -335,7 +346,7 @@ void handleModeChange() { //Hoverboard powering switch(state_modechange) { case 0: - if (requestmode==on && adc_throttle > ADC_CALIB_THROTTLE_LOWEST) { //requested to turn on but throttle is pressed + if (requestmode==on && (adc_throttle > ADC_CALIB_THROTTLE_LOWEST || adc_brake > ADC_CALIB_BRAKE_MIN) ) { //requested to turn on but throttle or brake is pressed state_modechange=0; requestmode=currentmode; //abort modechange //TODO: led show aborted modechange @@ -427,6 +438,8 @@ void handleModeChange() { void modeloops() { if (loopmillis - last_looptime >= LOOPTIME) { last_looptime=loopmillis; + //loop_test(); //for testing (adc calibration prints). comment out following switch case + switch (currentmode) { //mode changes case booting: break; @@ -452,16 +465,16 @@ void loop_idle() { void loop_on() { int _maxspeed=1000; + int _maxbrake=400; if (MODESWITCH_DOWN) { _maxspeed=200; + _maxbrake=200; } - int16_t speedvalue=constrain( map(adc_throttle, ADC_CALIB_THROTTLE_MIN, ADC_CALIB_THROTTLE_MAX, 0, _maxspeed ) ,0, _maxspeed); - /*int16_t lastSpeed=(out_speedFL+out_speedFR+out_speedRL+out_speedRR)/4; - - if (speedvalue<=lastSpeed) { //braking - speedvalue = (lastSpeed-speedvalue)>MAXBRAKERATE ? (lastSpeed-MAXBRAKERATE):speedvalue; - }*/ - + int16_t throttlevalue=constrain( map(adc_throttle, ADC_CALIB_THROTTLE_MIN, ADC_CALIB_THROTTLE_MAX, 0, _maxspeed ) ,0, _maxspeed); + + int16_t brakevalue=constrain( map(adc_brake, ADC_CALIB_BRAKE_MIN, ADC_CALIB_BRAKE_MAX, 0, _maxbrake ) ,0, _maxbrake); //positive value for braking + + int16_t speedvalue=throttlevalue*(1- (((float)brakevalue)/_maxbrake)) - (brakevalue*(1- (((float)throttlevalue)/_maxspeed)) ); //brake reduces throttle and adds negative torque out_speedFL=speedvalue; out_speedFR=speedvalue; @@ -472,7 +485,26 @@ void loop_on() { void loop_error() { out_speedFL=out_speedFR=out_speedRR=out_speedRL=0; //stop motors - Serial.print("Error:"); Serial.println(errormessage); + Serial.print("Error:"); Serial.println(errormessage); +} + +void loop_test() { + Serial.print("adc_throttle_raw="); Serial.print(adc_throttle_raw); + Serial.print(", adc_brake_raw="); Serial.print(adc_brake_raw); + + int _maxspeed=1000; + int _maxbrake=400; + if (MODESWITCH_DOWN) { + _maxspeed=200; + _maxbrake=200; + } + int16_t throttlevalue=constrain( map(adc_throttle, ADC_CALIB_THROTTLE_MIN, ADC_CALIB_THROTTLE_MAX, 0, _maxspeed ) ,0, _maxspeed); + + + int16_t brakevalue=constrain( map(adc_brake, ADC_CALIB_BRAKE_MIN, ADC_CALIB_BRAKE_MAX, 0, _maxbrake ) ,0, _maxbrake); //positive value for braking + + int16_t speedvalue=throttlevalue*(1- (((float)brakevalue)/_maxbrake)) - (brakevalue*(1- (((float)throttlevalue)/_maxspeed)) ); //brake reduces throttle and adds negative torque + Serial.print(", throttle="); Serial.print(throttlevalue); Serial.print(", brake="); Serial.print(brakevalue); Serial.print(", speed="); Serial.println(speedvalue); } void loop_off() { @@ -489,7 +521,7 @@ boolean boardsPowered() void failChecks() { #define FAILCHECK_WAITCHECK_AFTER_POWEROFF_TIME 3000 //time to start failchecking boardpower after board poweroff - #define FAILCHECK_RECEIVERECENT_TIME 1000 //should be less than FAILCHECK_WAITCHECK_AFTER_POWEROFF_TIME + #define FAILCHECK_RECEIVERECENT_TIME 1000 //timeout .should be less than FAILCHECK_WAITCHECK_AFTER_POWEROFF_TIME // ## Check if board is really offline ## if (!board1Enabled) { //board should be offline if (loopmillis-board1lastPoweroff > FAILCHECK_WAITCHECK_AFTER_POWEROFF_TIME){ //wait some time before checking if board did power off