Jon Freeman / Mbed 2 deprecated Brute_TS_Controller_2018_11

Dependencies:   TS_DISCO_F746NG mbed Servo LCD_DISCO_F746NG BSP_DISCO_F746NG QSPI_DISCO_F746NG AsyncSerial FastPWM

Revision:
5:21a8ac83142c
Parent:
4:67478861c670
Child:
6:57dc760effd4
--- a/main.cpp	Mon Apr 09 07:51:37 2018 +0000
+++ b/main.cpp	Tue May 01 08:34:36 2018 +0000
@@ -17,49 +17,51 @@
 */
 #include "mbed.h"
 #include "Electric_Loco.h"
-#include "FastPWM.h"
+#include "AsyncSerial.hpp"
+#include "Servo.h"
 #include "TS_DISCO_F746NG.h"
 #include "LCD_DISCO_F746NG.h"
+#include <cctype>
 
 LCD_DISCO_F746NG    lcd;
 TS_DISCO_F746NG     touch_screen;
 
-FastPWM     maxv    (D12, 1), 
-            maxi    (D11, 1); //  pin, prescaler value
-Serial      pc      (USBTX, USBRX);    //  Comms to 'PuTTY' or similar comms programme on pc
+//FastPWM     maxv    (D12, 1), 
+//            maxi    (D11, 1); //  pin, prescaler value
+Serial      pc      (USBTX, USBRX);    //  AsyncSerial does not work here. Comms to 'PuTTY' or similar comms programme on pc
 
-DigitalOut  reverse_pin     (D7);   //
-DigitalOut  forward_pin     (D6);   //these two decode to fwd, rev, regen_braking and park
+DigitalOut  reverse_pin     (D7);   //  These pins no longer used to set mode and direction, now commands issued to com
+DigitalOut  forward_pin     (D9);   //was D6, these two decode to fwd, rev, regen_braking and park
 
-/*New Nov 2017
-D14 and D15 not taken for CAN bus - bug given back because CAN bus doesn't work!
-*/
-//DigitalOut  GfetT2          (D14);  //  a horn
-//DigitalOut  GfetT1          (D15);  //  another horn
-DigitalOut led_grn          (LED1); //  the only on board user led
+DigitalOut  I_sink1          (D14);  //  a horn
+DigitalOut  I_sink2          (D15);  //  another horn
+DigitalOut  I_sink3          (D3);
+DigitalOut  I_sink4          (D4);
+DigitalOut  I_sink5          (D5);
+DigitalOut led_grn           (LED1); //  the only on board user led
 
-DigitalIn   f_r_switch      (D0);   //  Reads position of centre-off ignition switch
+DigitalIn   f_r_switch      (D2);   //  was D0, Reads position of centre-off ignition switch
 //DigitalIn   spareio_d8      (D8);
-//DigitalOut  throttle_servo_pulse_out    (D8);   //  now defined in throttle.cpp
-DigitalIn   spareio_d9      (D9);
+//DigitalIn   spareio_d9      (D9);
 DigitalIn   spareio_d10     (D10);  //  D8, D9, D10 wired to jumper on pcb - not used to Apr 2017
 
 AnalogIn    ht_volts_ain    (A0);  //  Jan 2017
 AnalogIn    ht_amps_ain     (A1);  //  Jan 2017
-AnalogIn    spare_ain2      (A2);
-AnalogIn    spare_ain3      (A3);
+//AnalogIn    spare_ain2      (A2);
+//AnalogIn    spare_ain3      (A3);
 //AnalogIn    spare_ain4      (A4);   //  hardware on pcb for these 3 spare analogue inputs - not used to Apr 2017
 //AnalogIn    spare_ain5      (A5); //  causes display flicker !
-Serial  com (A4, A5);   //  Com port to opto isolators on Twin BLDC Controller boards
+
+
+AsyncSerial  com (A4, A5);   //  Com port to opto isolators on Twin BLDC Controller boards
+//AsyncSerial  ir  (D1, D0);    //  Second port does work, but gives the old broken-up display flicker nonsense problem
 
 /*
 Speed now read via opto serial ports
+*/
 
-InterruptIn mot4hall    (D2);   //  One Hall sensor signal from each motor fed back to measure speed
-InterruptIn mot3hall    (D3);
-InterruptIn mot2hall    (D4);
-InterruptIn mot1hall    (D5);
-*/
+Servo   servo1    (D6);     //  Now used to adjust Honda speed
+
 extern  bool    odometer_zero   ()  ;   //  Returns true on success
 extern  bool    odometer_update  (uint32_t pulsetot, uint16_t pow, uint16_t volt)  ;   //  Hall pulse total updated once per sec and saved in blocks of 4096 bytes on QSPI onboard memory
 
@@ -75,17 +77,10 @@
 extern  void    SliderGraphic (struct slide & q)   ;
 extern  void    vm_set  ()  ;
 extern  void    update_meters  (double, double, double)  ;
-extern  void    command_line_interpreter    ()  ;
-
-extern  int     throttle    (double, double)    ;   //  called from main every 31ms
 
 static  const   int
     DAMPER_DECAY        = 42,   //  Small num -> fast 'viscous damper' on dead-mans function with finger removed from panel
     MAF_PTS             = 140,      //  Moving Average Filter points. Filters reduce noise on volatage and current readings
-    PWM_HZ              = 16000,    //  chosen to be above cutoff frequency of average human ear
-//    PWM_HZ            = 2000,   //  Used this to experiment on much bigger motor
-//    MAX_PWM_TICKS       = 108000000 / PWM_HZ,   //  108000000 for F746N, due to cpu clock = 216 MHz
-    MAX_PWM_TICKS       = SystemCoreClock / (2 * PWM_HZ),   //  108000000 for F746N, due to cpu clock = 216 MHz
     FWD                 = 0,
     REV                 = ~FWD;
 
@@ -94,100 +89,69 @@
 
 
 int     V_maf[MAF_PTS + 2],    I_maf[MAF_PTS + 2],  maf_ptr = 0;    //  ********* These should be uint16_t
-//uint32_t Hall_pulse[8] = {0,0,0,0,0,0,0,0};  //  more than max number of motors
-uint32_t Hall_pulse[8] = {1,1,1,1,1,1,1,1};  //  more than max number of motors
-uint32_t    historic_distance = 0;
-double  last_pwm = 0.0;
+uint32_t    sys_timer_32Hz = 0;
+double  last_V = 0.0, last_I = 0.0, recent_distance = 0.0;
 
 bool    qtrsec_trig                 = false;
 bool    trigger_current_read        = false;
 volatile    bool    trigger_32ms    = false;
 
-
-class   speed_measurement       //  Interrupts at qtr sec cause read of Hall_pulse counters which are incremented by transitions of Hall inputs
+class   speed_2018
 {
-    static const int    SPEED_AVE_PTS   = 9;    //  AVE_PTS - points in moving average filters
-    int speed_maf_mem   [(SPEED_AVE_PTS + 1) * 2][NUMBER_OF_MOTORS],
-        latest_counter_read[NUMBER_OF_MOTORS],
-        prev_counter_read[NUMBER_OF_MOTORS],
-        mafptr;
-    int raw_filtered    ()  ;              //  sum of count for all motors
-
+    static const int    SPEED_AVE_PTS   = 5;    //  AVE_PTS - points in moving average filters
+    uint32_t    speed_maf_mem   [(SPEED_AVE_PTS + 1) * 2][NUMBER_OF_MOTORS],
+                axle_total  [4],
+                mafptr;
+    double      average_rpm_out;
 public:
-
-    speed_measurement   ()  {
+    speed_2018  ()  {   //  Constructor
         memset(speed_maf_mem, 0, sizeof(speed_maf_mem));
+        axle_total[0] = axle_total[1] = axle_total[2] = axle_total[3] = 0;
         mafptr = 0;
-        memset  (latest_counter_read, 0, sizeof(latest_counter_read));
-        memset  (prev_counter_read, 0, sizeof(prev_counter_read));
-    }  //  constructor
-    int raw_filtered    (int)  ;              //  count for one motor
-    int RPM ()    ;
-    double MPH  ()  ;
-    void qtr_sec_update ()  ;
-    uint32_t    metres_travelled ();
-    uint32_t    pulse_total ();
+        average_rpm_out = 0.0;
+    }
+    void    rpm_update(struct parameters & a)  ;
+    double  mph ()  ;
 }
-speed   ;
+   speed2  ;
 
-int speed_measurement::raw_filtered  ()                 //  sum of count for all motors
-{
-    int result = 0, a, b;
-    for (b = 0; b < NUMBER_OF_MOTORS; b++)  {
-        for (a = 0; a < SPEED_AVE_PTS; a++)    {
-            result += speed_maf_mem[a][b];
-        }
+double  speed_2018::mph ()  {
+    int t[4] = {0,0,0,0};
+    for (int i = 0; i < SPEED_AVE_PTS; i++) {
+        t[0] += speed_maf_mem[i][0];
+        t[1] += speed_maf_mem[i][1];
+        t[2] += speed_maf_mem[i][2];
+        t[3] += speed_maf_mem[i][3];
     }
-    return  result;
+    int j = 0;
+    for (int i = 0; i < 4; i++) {
+        j += t[i];
+        axle_total[i] = t[i];
+    }
+    return  (rpm2mph * ((double) j) / (SPEED_AVE_PTS * 4));
 }
 
-int speed_measurement::raw_filtered  (int motor)    //  count for one motor
-{
-    int result = 0, a;
-    for (a = 0; a < SPEED_AVE_PTS; a++)    {
-        result += speed_maf_mem[a][motor];
+void    speed_2018::rpm_update(struct parameters & a)  {    //  Puts new readings into mem
+    if  (a.gp_i == 0)   {
+        speed_maf_mem   [mafptr][0] = (uint32_t)a.dbl[0];
+        speed_maf_mem   [mafptr][1] = (uint32_t)a.dbl[1];
     }
-    return  result;
-}
-
-double speed_measurement::MPH  ()
-{
-    return  rpm2mph * (double)RPM();
-}
-
-int speed_measurement::RPM  ()
-{
-    int rpm = raw_filtered  ();
-    rpm *= 60 * 4;              //  60 sec per min, 4 quarters per sec, result pulses per min
-    rpm /= (SPEED_AVE_PTS * NUMBER_OF_MOTORS * 8);  //  8 transitions counted per rev
-    return  rpm;
-}
-
-void speed_measurement::qtr_sec_update  ()      //  this to be called every quarter sec to read counters and update maf
-{
-    mafptr++;
-    if  (mafptr >= SPEED_AVE_PTS)
-        mafptr = 0;
-    for (int a = 0; a < NUMBER_OF_MOTORS; a++)  {
-        prev_counter_read[a]    = latest_counter_read[a];
-        latest_counter_read[a]  = Hall_pulse[a];
-        speed_maf_mem[mafptr][a] = latest_counter_read[a] - prev_counter_read[a];
+    else    {
+        speed_maf_mem   [mafptr][2] = (uint32_t)a.dbl[0];
+        speed_maf_mem   [mafptr][3] = (uint32_t)a.dbl[1];
+        mafptr++;
+        if  (mafptr >= SPEED_AVE_PTS)
+            mafptr = 0;
     }
 }
 
-uint32_t    speed_measurement::metres_travelled ()
-{
-    return  pulse_total() / (int)PULSES_PER_METRE;
+
+void    rpm_push    (struct parameters & a)  {  //  Latest RPM reports from Dual BLDC Motor Controllers arrive here
+    speed2.rpm_update   (a);
+//    pc.printf   ("RPM%d %d, mph %.1f\r\n", (int)a.dbl[0], (int)a.dbl[1], speed2.mph());
 }
 
-uint32_t    speed_measurement::pulse_total ()
-{
-    return  historic_distance + Hall_pulse[0] + Hall_pulse[1] + Hall_pulse[2] + Hall_pulse[3];
-}
 
-uint32_t    get_pulse_total ()  {   //  called by SD card code
-    return  speed.pulse_total();
-}
 
 void    set_V_limit (double p)  //  Sets max motor voltage
 {
@@ -195,25 +159,28 @@
         p = 0.0;
     if  (p > 1.0)
         p = 1.0;
-    last_pwm = p;
-    p *= 0.95;   //  need limit, ffi see MCP1630 data
-    p   = 1.0 - p;  //  because pwm is wrong way up
-    maxv.pulsewidth_ticks  ((int)(p * MAX_PWM_TICKS));  //  PWM output on pin D12 inverted motor pwm
+    last_V = p;
+    com.printf  ("v%d\r", (int)(p * 99.0));
+//    p *= 0.95;   //  need limit, ffi see MCP1630 data
+//    p   = 1.0 - p;  //  because pwm is wrong way up
+//    maxv.pulsewidth_ticks  ((int)(p * MAX_PWM_TICKS));  //  PWM output on pin D12 inverted motor pwm
 }
 
 void    set_I_limit (double p)     //  Sets max motor current
 {
-    int a;
+//    int a;
     if  (p < 0.0)
         p = 0.0;
     if  (p > 1.0)
         p = 1.0;
-    a = (int)(p * MAX_PWM_TICKS);
-    if  (a > MAX_PWM_TICKS)
-        a = MAX_PWM_TICKS;
-    if  (a < 0)
-        a = 0;
-    maxi.pulsewidth_ticks  (a);  //  PWM output on pin D12 inverted motor pwm
+    last_I = p;     //  New 30/4/2018 ; no use for this yet, included to be consistent with V
+    com.printf  ("i%d\r", (int)(p * 99.0));
+//    a = (int)(p * MAX_PWM_TICKS);
+//    if  (a > MAX_PWM_TICKS)
+//        a = MAX_PWM_TICKS;
+//    if  (a < 0)
+//        a = 0;
+//    maxi.pulsewidth_ticks  (a);  //  PWM output on pin D12 inverted motor pwm
 }
 
 double  read_ammeter ()
@@ -232,48 +199,21 @@
     for (int b = 0; b < MAF_PTS; b++)
         a += V_maf[b];
     a /= MAF_PTS;
-    double i = (double) a;
-    return  (i / 617.75) + 0.3;  //  fiddled to suit current module
+    double v = (double) a;
+//    return  (v / 940.0) + 0.3;  //  fiddled to suit resistor values
+    return  (v / 932.0) + 0.0;  //  fiddled to suit resistor values
 }
 
 //  Interrupt Service Routines
 
-void    ISR_mot1_hall_handler  ()   //  read motor position pulse signals from up to six motors
-{
-    Hall_pulse[0]++;
-}
-void    ISR_mot2_hall_handler  ()
-{
-    Hall_pulse[1]++;
-}
-void    ISR_mot3_hall_handler  ()
-{
-    Hall_pulse[2]++;
-}
-void    ISR_mot4_hall_handler  ()
-{
-    Hall_pulse[3]++;
-}
-void    ISR_mot5_hall_handler  ()   //  If only 4 motors this never gets used, there is no fifth motor
-{
-    Hall_pulse[4]++;
-}
-void    ISR_mot6_hall_handler  ()   //  As one above
-{
-    Hall_pulse[5]++;
-}
-
-
 void    ISR_current_reader  (void)      //  FIXED at 250us
 {
     static  int ms32 = 0, ms250 = 0;
     trigger_current_read    = true; //  every 250us, i.e. 4kHz  NOTE only sets trigger here, readings taken in main loop
     ms32++;
-    if  (ms32 > 124)    {
+    if  (ms32 > 124)    {   //  31.25ms, not 32ms, is 32Hz
         ms32 = 0;
-        
-        historic_distance++;
-        
+        sys_timer_32Hz++;   //  , usable anywhere as general measure of elapsed time
         trigger_32ms = true;
         ms250++;
         if  (ms250 > 7) {
@@ -303,24 +243,15 @@
     if  (!trigger_current_read)
         return;
     trigger_current_read = false;
+    int ch;
+    ch++;
     I_maf[maf_ptr] = ht_amps_ain.read_u16();
     V_maf[maf_ptr] = ht_volts_ain.read_u16();
     maf_ptr++;
     if  (maf_ptr > MAF_PTS - 1)
         maf_ptr = 0;
 }
-/*  Feb 2017, re-thought use of FR and SG signals. Rename these FWD and REV. Truth table for actions required now : -
-FWD(A5) REV(A4) PWM         Action
-    0   0       0    'Handbrake' - energises motor to not move
-    0   0       1    'Handbrake' - energises motor to not move
-    0   1       0    Reverse0
-    0   1       1    Reverse1
 
-    1   0       0    Forward0
-    1   0       1    Forward1
-    1   1       0    Regen Braking
-    1   1       1    Regen Braking
-*/
 void    set_run_mode    (int    mode)
 {   //  NOTE Nov 2017 - Handbrake not implemented
     if  (mode == HANDBRAKE_SLIPPING)    slider.handbrake_slipping = true;
@@ -330,15 +261,19 @@
 //        case    HANDBRAKE_SLIPPING:
 //            break;
         case    PARK:     //  PARKED new rom code IS now finished.
-            forward_pin = 0;
-            reverse_pin = 0;
+//            forward_pin = 0;
+//            reverse_pin = 0;
             slider.state = mode;
             set_V_limit     (0.075); // was 0.1
             set_I_limit (slider.handbrake_effort);
+//            char    tmp[16];
+//            sprintf (tmp, "vi7 %d\r", (int)(slider.handbrake_effort * 99.0));
+//            com.printf  ("%s", tmp);
             break;
         case    REGEN_BRAKE:    //  BRAKING, pwm affects degree
-            forward_pin = 1;
-            reverse_pin = 1;
+            com.printf  ("rb\r");
+//            forward_pin = 1;
+//            reverse_pin = 1;
             slider.state = mode;
             break;
         case    NEUTRAL_DRIFT:
@@ -348,11 +283,13 @@
             break;
         case    RUN:
             if  (slider.direction)  {
-                forward_pin = 0;
-                reverse_pin = 1;
+                com.printf  ("fw\r");
+//                forward_pin = 0;
+//                reverse_pin = 1;
             } else    {
-                forward_pin = 1;
-                reverse_pin = 0;
+                com.printf  ("re\r");
+//                forward_pin = 1;
+//                reverse_pin = 0;
             }
             slider.state = mode;
             break;
@@ -362,62 +299,25 @@
 }
 
 
-#ifdef  SDCARD
-
-#define BLOCK_START_ADDR         0     /* Block start address      */
-#define NUM_OF_BLOCKS            5     /* Total number of blocks   */
-#define BUFFER_WORDS_SIZE        ((BLOCKSIZE * NUM_OF_BLOCKS) >> 2) /* Total data size in bytes */
- 
-uint32_t aTxBuffer[BUFFER_WORDS_SIZE];
-uint32_t aRxBuffer[BUFFER_WORDS_SIZE];
-/* Private function prototypes -----------------------------------------------*/
-void SD_main_test(void);
-void SD_Detection(void);
-
-static void Fill_Buffer(uint32_t *pBuffer, uint32_t uwBufferLenght, uint32_t uwOffset);
-static uint8_t Buffercmp(uint32_t* pBuffer1, uint32_t* pBuffer2, uint16_t BufferLength);
-/**
-  * @brief  Fills buffer with user predefined data.
-  * @param  pBuffer: pointer on the buffer to fill
-  * @param  uwBufferLenght: size of the buffer to fill
-  * @param  uwOffset: first value to fill on the buffer
-  * @retval None
-  */
-static void Fill_Buffer(uint32_t *pBuffer, uint32_t uwBufferLength, uint32_t uwOffset)
-{
-  uint32_t tmpIndex = 0;
-
-  /* Put in global buffer different values */
-  for (tmpIndex = 0; tmpIndex < uwBufferLength; tmpIndex++ )
-  {
-    pBuffer[tmpIndex] = tmpIndex + uwOffset;
-  }
-}
- 
-/**
-  * @brief  Compares two buffers.
-  * @param  pBuffer1, pBuffer2: buffers to be compared.
-  * @param  BufferLength: buffer's length
-  * @retval 1: pBuffer identical to pBuffer1
-  *         0: pBuffer differs from pBuffer1
-  */
-static uint8_t Buffercmp(uint32_t* pBuffer1, uint32_t* pBuffer2, uint16_t BufferLength)
-{
-  while (BufferLength--)
-  {
-    if (*pBuffer1 != *pBuffer2)
-    {
-      return 1;
-    }
-
-    pBuffer1++;
-    pBuffer2++;
-  }
-
-  return 0;
+void    throttle    (double p)  {            // New Apr 2018 ; servo adjusts throttle lever on Honda GX120
+const   double  THR_MAX = 0.92;
+const   double  THR_MIN = 0.09;
+const   double  RANGE = THR_MAX - THR_MIN;
+    if  (p > 1.0)
+        p = 1.0;
+    if  (p < 0.0)
+        p = 0.0;
+    //  p = 1.0 - p;    //  if direction needs swapping
+    p *= RANGE;
+    p += THR_MIN;
+    servo1 = p;
 }
 
-#endif
+
+extern  void    setup_pccom ()  ;
+extern  void    setup_lococom ()  ;
+extern  void    clicore (struct parameters & a) ;
+extern  struct  parameters pccom, lococom;
 
 int main()
 {
@@ -497,67 +397,6 @@
     pc.printf   ("\r\r\r\n");
 #endif
 
-#ifdef  SDCARD
-    uint8_t SD_state;
-    SD_state = sd.Init();
-    if(SD_state != MSD_OK){
-        if(SD_state == MSD_ERROR_SD_NOT_PRESENT){
-            pc.printf("SD shall be inserted before running test\r\n");
-        } else {
-            pc.printf("SD Initialization : FAIL.\r\n");
-        }
-        pc.printf("SD Test Aborted.\r\n");
-    } else {
-        pc.printf("SD Initialization : OK.\r\n");
-
-        SD_state = sd.Erase(BLOCK_START_ADDR, (BLOCK_START_ADDR + NUM_OF_BLOCKS - 1));
-
-        /* Wait until SD card is ready to use for new operation */
-        while(sd.GetCardState() != SD_TRANSFER_OK){
-        }
-        if (SD_state != MSD_OK){
-            pc.printf("SD ERASE : FAILED.\r\n");
-            pc.printf("SD Test Aborted.\r\n");
-        } else {
-            pc.printf("SD ERASE : OK.\r\n");
-          
-            /* Fill the buffer to write */
-            Fill_Buffer(aTxBuffer, BUFFER_WORDS_SIZE, 0x2300);
-          
-            SD_state = sd.WriteBlocks(aTxBuffer, BLOCK_START_ADDR, NUM_OF_BLOCKS, 10000);
-            /* Wait until SD card is ready to use for new operation */
-            while(sd.GetCardState() != SD_TRANSFER_OK){
-            }
-
-            if (SD_state != MSD_OK){
-                pc.printf("SD WRITE : FAILED.\r\n");
-                pc.printf("SD Test Aborted.\r\n");
-            } else {
-                pc.printf("SD WRITE : OK.\r\n");
-            
-                SD_state = sd.ReadBlocks(aRxBuffer, BLOCK_START_ADDR, NUM_OF_BLOCKS, 10000);
-                /* Wait until SD card is ready to use for new operation */
-                while(sd.GetCardState() != SD_TRANSFER_OK){
-                }
-
-                if (SD_state != MSD_OK){
-                    pc.printf("SD READ : FAILED.\r\n");
-                    pc.printf("SD Test Aborted.\r\n");
-                } else {
-                    pc.printf("SD READ : OK.\r\n");
-                    if(Buffercmp(aTxBuffer, aRxBuffer, BUFFER_WORDS_SIZE) > 0){
-                        pc.printf("SD COMPARE : FAILED.\r\n");
-                        pc.printf("SD Test Aborted.\r\n");
-                    } else {
-                        pc.printf("SD Test : OK.\r\n");
-                        pc.printf("SD can be removed.\r\n");
-                    }
-                }
-            }
-        }
-    }
-    pc.printf   ("\r\n");
-#endif  
 
     int qtr_sec = 0, seconds = 0, minutes = 0;
     double  electrical_power_Watt = 0.0;
@@ -566,40 +405,44 @@
     memset  (&kybd_b, 0, sizeof(kybd_b));
 
 //    spareio_d8.mode (PullUp); now output driving throttle servo
-    spareio_d9.mode (PullUp);
+//    spareio_d9.mode (PullUp);
     spareio_d10.mode(PullUp);
 
     Ticker  tick250us;
 
 //  Setup User Interrupt Vectors
-    mot1hall.fall       (&ISR_mot1_hall_handler);
-    mot1hall.rise       (&ISR_mot1_hall_handler);
-    mot2hall.fall       (&ISR_mot2_hall_handler);
-    mot2hall.rise       (&ISR_mot2_hall_handler);
-    mot3hall.fall       (&ISR_mot3_hall_handler);
-    mot3hall.rise       (&ISR_mot3_hall_handler);
-    mot4hall.fall       (&ISR_mot4_hall_handler);
-    mot4hall.rise       (&ISR_mot4_hall_handler);
-
     tick250us.attach_us (&ISR_current_reader, 250);    //  count 125 of these to trig 31.25ms
 //    tick32ms.attach_us  (&ISR_tick_32ms, 32001);
 //    tick32ms.attach_us  (&ISR_tick_32ms, 31250);    //  then count 8 pulses per 250ms
 //    tick250ms.attach_us (&ISR_tick_250ms, 250002);
     pc.baud (9600);
-//    GfetT1 = 0;
-//    GfetT2 = 0;     //  two output bits for future use driving horns
+    com.baud (19200);
+//    ir.baud (1200);
+    
+    I_sink1 = 0;    //  turn outputs off
+    I_sink2 = 0;
+    I_sink3 = 0;
+    I_sink4 = 0;
+    I_sink5 = 0;
     if  (f_r_switch)
         slider.direction = FWD; //  make decision from key switch position here
     else
         slider.direction = REV; //  make decision from key switch position here
 
 //    max_pwm_ticks   = SystemCoreClock / (2 * PWM_HZ);  //  prescaler min value is 2, or so it would seem. SystemCoreClock returns 216000000 on F746NG board
-    maxv.period_ticks      (MAX_PWM_TICKS + 1);  //  around 18 kHz
-    maxi.period_ticks      (MAX_PWM_TICKS + 1);
+//    maxv.period_ticks      (MAX_PWM_TICKS + 1);  //  around 18 kHz
+//    maxi.period_ticks      (MAX_PWM_TICKS + 1);
     set_I_limit (0.0);
     set_V_limit (0.0);
-
-    pc.printf   ("Jon's Touch Screen Loco 2017 sytem starting up %s\r\n", slider.direction ? "Forward":"Reverse");
+    if  (slider.direction)
+        com.printf  ("fw\r");
+    else
+        com.printf  ("re\r");
+//    com.printf  ("rvi22 55\rkd\r");
+    throttle    (0.0);      //  Set revs to idle. Start engine and warm up before powering up control
+    setup_pccom   ();
+    setup_lococom ();
+    pc.printf   ("Jon's Touch Screen Loco 2018 sytem starting up %s\r\n", slider.direction ? "Forward":"Reverse");
     uint8_t lcd_status = touch_screen.Init(lcd.GetXSize(), lcd.GetYSize());
     if (lcd_status != TS_OK) {
         lcd.Clear(LCD_COLOR_RED);
@@ -629,31 +472,59 @@
 
     vm_set();   //  Draw 3 analogue meter movements, speedo, voltmeter, ammeter
 
-#ifdef  SDCARD
-//    mainSDtest();
-#endif
-
 //    odometer_zero   ();
 //    pc.printf   ("Back from odometer_zero\r\n");
     double  torque_req = 0.0;
     bool    toggle32ms = false;
     //  Main loop
-extern  void    show_all_banks () ;
-//    show_all_banks  ();
+
+    int boards_fitted[8], bfptr = 0;
+    for (int i = 0; i < 8; i++)
+        boards_fitted[i] = 0;
+    sys_timer_32Hz  = 0;
+
+    int     last_digit = 0, board_cnt = 0, ch;
+    while   (sys_timer_32Hz < 12)   {       //  Sniff out system, discover motor controllers connected
+        while   (!trigger_32ms)
+//            command_line_interpreter    ();
+            clicore    (pccom);
+        trigger_32ms = false;
+        if  (sys_timer_32Hz < 11)   {       //  issue "0who\r", "1who\r" ... "9who\r"
+            com.putc    ((sys_timer_32Hz - 1) | '0');
+            com.printf  ("who\r");
+        }
+        while   (com.readable())  {
+            ch = com.getc();
+            if  (ch != '\r') {
+                if  (isdigit(ch))
+                    last_digit = ch;
+            }
+            else    {   //  got '\r' at end of line
+                if  (isdigit(last_digit))
+                    boards_fitted[board_cnt++] = last_digit;
+                last_digit = 0;
+            }
+        }
+    }
+    while   (boards_fitted[bfptr])    { //  This works, identified BLDC Motor Controller board ID chars '0' to '9' listed in boards_fitted[]
+        pc.printf   ("Board %c found\r\n", boards_fitted[bfptr++]);
+    }
+    clicore (pccom);
+    pc.printf   ("pcmenuitems %d, commenuitems %d\r\n", pccom.numof_menu_items, lococom.numof_menu_items);
+    //  Done setup, time to roll !
     
     while (1) {
 
         struct ky_bd * present_kybd, * previous_kybd;
         bool    sliderpress = false;
-        command_line_interpreter    ()  ;   //  Do any actions from command line via usb link
+//        command_line_interpreter    ()  ;   //  Do any actions from command line via usb link
+        clicore (pccom);
+
         stuff_to_do_every_250us     ()  ;
 
         if  (trigger_32ms == true)  {       //  Stuff to do every 32 milli secs
             trigger_32ms = false;
-
-//  CALL THROTTLE HERE  - why here ? Ah yes, this initiates servo pulse. Need steady stream of servo pulses even when nothing changes.
-            throttle    (torque_req, 2.3);
-
+        clicore (lococom);
             toggle32ms = !toggle32ms;
             if  (toggle32ms)    {
                 present_kybd = &kybd_a;
@@ -679,8 +550,10 @@
                     k = present_kybd->slider_y;     //  get position of finger on slider
                     if  (slider.state == RUN && k != slider.position)       //  Finger has moved within RUN range
                         slider.recalc_run   = true;
-                    if  (slider.state == RUN && k >= NEUTRAL_VAL)       //  Finger has moved from RUN to BRAKE range
+                    if  (slider.state == RUN && k >= NEUTRAL_VAL)   {       //  Finger has moved from RUN to BRAKE range
                         slider.position = k = NEUTRAL_VAL;          //  kill drive for rapid reaction to braking
+                        throttle    (0.0);
+                    }
 
                     else    {           //  nice slow non-jerky glidey movement required
                         dbl = (double)(k - slider.position);
@@ -704,6 +577,7 @@
                         /* set_pwm (brake_effort); */
                         set_V_limit (sqrt(brake_effort));   //  sqrt gives more linear feel to control
                         set_I_limit (1.0);
+                        throttle    (0.0);
                     }
                 }   else    {   //                pc.printf   ("Slider not touched\r\n");
                 }
@@ -714,10 +588,10 @@
                     if  (inlist(*present_kybd, k))    {
                         switch  (k)    {    //  Here for auto-repeat type key behaviour
                             case    21:     //  key is 'voltmeter'
-//                                set_V_limit (last_pwm * 1.002 + 0.001);
+//                                set_V_limit (last_V * 1.002 + 0.001);
                                 break;
                             case    22:     //  key is 'ammeter'
-//                                set_V_limit (last_pwm * 0.99);
+//                                set_V_limit (last_V * 0.99);
                                 break;
                         }   //  endof switch (k)
                     }       //  endof if (inlist(*present2, k)) {
@@ -769,23 +643,32 @@
                 b = NEUTRAL_VAL - b;    //  now got integer going positive for increasing power demand
                 torque_req = (double) b;
                 torque_req /= (NEUTRAL_VAL - MIN_POS);  //  in range 0.0 to 1.0
-                pc.printf   ("torque_rec = %.3f, last_pwm = %.3f\r\n", torque_req, last_pwm);
+                pc.printf   ("torque_rec = %.3f, last_V = %.3f\r\n", torque_req, last_V);
                 set_I_limit (torque_req);
+                
+                throttle    (torque_req);   //  Think about moderating this and including speed related element
+                
                 if  (torque_req < 0.05)
-                    set_V_limit (last_pwm / 2.0);
+                    set_V_limit (last_V / 2.0);
                 else    {
-                    if  (last_pwm < 0.99)
-                        set_V_limit (last_pwm + 0.05);   //  ramp voltage up rather than slam to max
+                    if  (last_V < 0.99)
+                        set_V_limit (last_V + 0.05);   //  ramp voltage up rather than slam to max
                 }
             }
         }       //  endof doing 32ms stuff
 
         if  (qtrsec_trig == true)  {    //  do every quarter second stuff here
             qtrsec_trig = false;
-            speed.qtr_sec_update  ();
-            double  speedmph = speed.MPH(), amps = 0.0 - read_ammeter(), volts = read_voltmeter();
+//            speed.qtr_sec_update  ();
+//            double  speedmph = speed.MPH(), amps = 0.0 - read_ammeter(), volts = read_voltmeter();
+            double  speedmph = speed2.mph(), amps = 0.0 - read_ammeter(), volts = read_voltmeter();
 //static const double mph_2_mm_per_sec = 447.04;  //  exact
 //            double  mm_travelled_in_qtrsec = speedmph * mph_2_mm_per_sec / 4.0;
+//  1.0 mph = 0.44704 metre per sec
+//          = 0.11176 metre per quarter sec
+
+            recent_distance += (speedmph * 111.76);    //  Convert mph to distance mm travelled in quarter second
+
             slider.loco_speed = speedmph;
             electrical_power_Watt = volts * amps;   //  visible throughout main
             update_meters  (speedmph, electrical_power_Watt, volts)  ;   //  displays speed, volts and power (volts times amps)
@@ -804,31 +687,43 @@
                     pc.printf   ("Handbrake not slipping, effort %.2f\r\n", slider.handbrake_effort);
                 }
             }
+            switch  (qtr_sec)   {   //  Can do sequential stuff quarter second apart here
+                case    0:
+                case    2:
+                    com.putc    (boards_fitted[0]);
+                    com.printf  ("rpm\r");
+                    break;
+                case    1:
+                case    3:
+                    com.putc    (boards_fitted[1]);
+                    com.printf  ("rpm\r");
+                    break;
+                default:
+                    qtr_sec = 0;
+                    break;
+            }   //  End of switch qtr_sec
             qtr_sec++;
             //  Can do stuff once per second here
             if(qtr_sec > 3) {
                 qtr_sec = 0;
                 seconds++;
+                com.printf  ("kd\r");       //  Kick the WatchDog timers in the Twin BLDC drive boards
                 if  (seconds > 59)  {
                     seconds = 0;
                     minutes++;
                     //  do once per minute stuff here
                 }   //  fall back into once per second
 #ifdef  QSPI
+/*
+    Odometer Update stuff now needs fixing to take updagte in form of mm travelled in previous period
+    
 //bool    odometer_update  (uint32_t pulsetot, uint16_t pow, uint16_t volt)  ;   //  Hall pulse total updated once per sec and saved in blocks of 4096 bytes on QSPI onboard memory
                 if  (!odometer_update (historic_distance, (uint16_t)electrical_power_Watt, (uint16_t)(volts * 500.0)))
                     pc.printf   ("Probs with odometer_update");
                 char    dist[20];
-                sprintf (dist, "%05d m", speed.metres_travelled());
+//                sprintf (dist, "%05d m", speed.metres_travelled());
                 displaytext (236, 226, 2, dist);
-#endif
-#ifdef  SDCARD
-                if(SD_state == MSD_OK) {
-                    char    dist[20];
-                    sprintf (dist, "%05d m", speed.metres_travelled());
-                    displaytext (236, 226, 2, dist);
-                    update_SD_card   ();    //  Buffers data for SD card, writes when buffer filled
-                }
+*/
 #endif
 //                calc_motor_amps( mva);
             }   //  endof if(qtr_sec > 3