Dual Brushless Motor ESC, 10-62V, up to 50A per motor. Motors ganged or independent, multiple control input methods, cycle-by-cycle current limit, speed mode and torque mode control. Motors tiny to kW. Speed limit and other parameters easily set in firmware. As used in 'The Brushless Brutalist' locomotive - www.jons-workshop.com. See also Model Engineer magazine June-October 2019.

Dependencies:   mbed BufferedSerial Servo PCT2075 FastPWM

Update 17th August 2020 Radio control inputs completed

Revision:
5:ca86a7848d54
Parent:
4:21d91465e4b1
Child:
6:f289a49c1eae
--- a/main.cpp	Thu Apr 26 08:23:04 2018 +0000
+++ b/main.cpp	Tue May 29 16:36:34 2018 +0000
@@ -3,8 +3,15 @@
 #include "BufferedSerial.h"
 #include "FastPWM.h"
 #include "Servo.h"
+
+/*
+New 29th May 2018 - YET TO CODE FOR - Fwd/Rev line from possible remote hand control box has signal routed to T5
+                Also new LMT01 temperature sensor routed to T1
+*/
+
+
 /*  STM32F401RE - compile using NUCLEO-F401RE
-//  PROJECT -   Dual Brushless Motor Controller -   March 2018.
+//  PROJECT -   Dual Brushless Motor Controller -   Jon Freeman     April 2018.
 
 AnalogIn to read each motor current
 
@@ -23,23 +30,18 @@
 */
 
 //  Hoped to select servo functions from user info stored on EEROM. Too difficult. Do not define servo as in and out
-//#define SERVO1_IN
-//#define SERVO1_OUT
-//#define SERVO2_IN
-//#define SERVO2_OUT
-
 
 //  Port A -> MotorA, Port B -> MotorB
 const   uint16_t
 AUL = 1 << 0,   //  Feb 2018 Now using DGD21032 mosfet drivers via 74HC00 pwm gates (low side) - GOOD, works well with auto-tickle of high side drivers
-AVL = 1 << 6,
+AVL = 1 << 6,   //  These are which port bits connect to which mosfet driver
 AWL = 1 << 4,
 
 AUH = 1 << 1,
 AVH = 1 << 7,
 AWH = 1 << 8,
 
-AUV =   AUH | AVL,
+AUV =   AUH | AVL,  //  Each of 6 possible output energisations made up of one hi and one low
 AVU =   AVH | AUL,
 AUW =   AUH | AWL,
 AWU =   AWH | AUL,
@@ -49,9 +51,9 @@
 KEEP_L_MASK_A   = AUL | AVL | AWL,
 KEEP_H_MASK_A   = AUH | AVH | AWH,
 
-BRA = AUL | AVL | AWL,
+BRA = AUL | AVL | AWL,  //  All low side switches on (and all high side off) for braking
 
-BUL = 1 << 0,
+BUL = 1 << 0,   //  Likewise for MotorB but different port bits on different port
 BVL = 1 << 1,
 BWL = 1 << 2,
 
@@ -74,7 +76,7 @@
 PORT_A_MASK = AUL | AVL | AWL | AUH | AVH | AWH,            //  NEW METHOD FOR DGD21032 MOSFET DRIVERS
 PORT_B_MASK = BUL | BVL | BWL | BUH | BVH | BWH;
 
-PortOut MotA    (PortA, PORT_A_MASK);
+PortOut MotA    (PortA, PORT_A_MASK);   //  Activate output ports to motor drivers
 PortOut MotB    (PortB, PORT_B_MASK);
 
 //  Pin 1   VBAT    NET +3V3
@@ -86,7 +88,7 @@
 //  Pin 7   NRST            NET NRST
 AnalogIn    Ain_DriverPot   (PC_0); //  Pin 8   Spare Analogue in, net SAIN fitted with external pull-down
 AnalogIn    Ain_SystemVolts (PC_1); //  Pin 9
-AnalogIn    Motor_A_Current (PC_2); //  Pin 10  might as well use up WSRA stock here
+AnalogIn    Motor_A_Current (PC_2); //  Pin 10
 AnalogIn    Motor_B_Current (PC_3); //  Pin 11
 //  Pin 12 VSSA/VREF-   NET GND
 //  Pin 13 VDDA/VREF+   NET +3V3
@@ -129,12 +131,15 @@
 //  Feb 2018 Pins 44 and 45 now liberated, could use for serial or other uses
 //BufferedSerial  extra_ser   (PA_11, PA_12);    //  Pins 44, 45  tx, rx to XBee module
 DigitalOut  T2  (PA_11);    //  Pin 44
-DigitalOut  T1  (PA_12);    //  Pin 45
+// was DigitalOut  T1  (PA_12);    //  Pin 45
+InterruptIn T1  (PA_12);    //  Pin 45 now input counting pulses from LMT01 temperature sensor
 //  Pin 46  SWDIO
 //  Pin 47  VSS
 //  Pin 48  VDD
 //  Pin 49  SWCLK
-DigitalOut  T5  (PA_15); //  Pin 50
+
+//Was DigitalOut  T5  (PA_15); //  Pin 50
+DigitalIn   T5  (PA_15); //  Pin 50 now fwd/rev from remote control box if fitted
 InterruptIn MAH1    (PC_10);    //  Pin 51
 InterruptIn MAH2    (PC_11);    //  Pin 52
 InterruptIn MAH3    (PC_12);    //  Pin 53
@@ -155,29 +160,18 @@
 //  Pin 64  VDD
 //  SYSTEM CONSTANTS
 
-/*  Please Do Not Alter these */
-const   int     VOLTAGE_READ_INTERVAL_US    = 50,       //  Interrupts timed every 50 micro sec, runs around loop performing 1 A-D conversion per pass
-                MAIN_LOOP_REPEAT_TIME_US    = 31250,    //  31250 us, with TACHO_TAB_SIZE = 32 means tacho_ticks_per_time is tacho_ticks_per_second
-                MAIN_LOOP_ITERATION_Hz      = 1000000 / MAIN_LOOP_REPEAT_TIME_US,
-                CURRENT_SAMPLES_AVERAGED    = 100,     //  Current is spikey. Reading smoothed by using average of this many latest current readings
-                PWM_HZ              = 16000,    //  chosen to be above cutoff frequency of average human ear
-                MAX_PWM_TICKS       = SystemCoreClock / PWM_HZ,
-                TICKLE_TIMES    =   100 ;
-
-/*  End of Please Do Not Alter these */
 
 /*  Global variable declarations */
 volatile    uint32_t    fast_sys_timer      = 0;    //  gets incremented by our Ticker ISR every VOLTAGE_READ_INTERVAL_US
+int         WatchDog    = WATCHDOG_RELOAD + 80; //  Allow extra few seconds at powerup
 uint32_t    volt_reading        = 0,    //  Global updated by interrupt driven read of Battery Volts
             driverpot_reading   = 0,    //  Global updated by interrupt driven read of Drivers Pot
             sys_timer           = 0,    //  gets incremented by our Ticker ISR every MAIN_LOOP_REPEAT_TIME_US
-            AtoD_Semaphore = 0;
+            AtoD_Semaphore      = 0;
+int         IAm;
 bool        loop_flag   = false;    //  made true in ISR_loop_timer, picked up and made false again in main programme loop
 bool        flag_8Hz    = false;    //  As loop_flag but repeats 8 times per sec
 
-double      angle = 0.0,    angle_step = 0.00005,  sinv, cosv;
-
-//double      test_pot = 0.0, test_amps = 0.0;    //  These used in knifeandfork code testing only
 /*  End of Global variable declarations */
 
 Ticker  tick_vread;     //  Device to cause periodic interrupts, used to time voltage readings etc
@@ -185,14 +179,6 @@
 
 //  Interrupt Service Routines
 
-/*uint32_t    edgeintcnt = 0;
-void    seredgerise ()  {   edgeintcnt++;   }
-void    seredgefall ()  {   edgeintcnt++;   }
-
-void    seredgetest ()  {
-    com2.printf ("edgeintcnt = %d\r\n", edgeintcnt);
-    com3.printf ("%c", 0x55);
-}*/
 /** void    ISR_loop_timer  ()
 *   This ISR responds to Ticker interrupts at a rate of (probably) 32 times per second (check from constant declarations above)
 *   This ISR sets global flag 'loop_flag' used to synchronise passes around main programme control loop.
@@ -212,21 +198,13 @@
 *   AtoD_reader() called from convenient point in code to take readings outside of ISRs
 */
 
-void    ISR_voltage_reader  ()      //  This is Ticker Interrupt Service Routine - few us between readings - VOLTAGE_READ_INTERVAL_US    = 50
+void    ISR_voltage_reader  ()      //  This is Ticker Interrupt Service Routine ; few us between readings ; VOLTAGE_READ_INTERVAL_US    = 50
 {
     AtoD_Semaphore++;
     fast_sys_timer++;        //  Just a handy measure of elapsed time for anything to use
 }
 
 
-/*
-Servo - mutex uses :
-0.  Unused
-1.  Input of pwm from model control Rx
-2.  Output pwm to drive model control servo
-*/
-enum    {SERVO_UNUSED, SERVO_IN, SERVO_OUT}  ;
-
 class   RControl_In
 {  //  Read servo style pwm input
     Timer   t;
@@ -318,7 +296,7 @@
 
 class   motor
 {
-    uint32_t    Hall_total, mode, edge_count_table[MAIN_LOOP_ITERATION_Hz]; //  to contain one seconds worth
+    uint32_t    Hall_total, visible_mode, inner_mode, edge_count_table[MAIN_LOOP_ITERATION_Hz]; //  to contain one seconds worth
     uint32_t    latest_pulses_per_sec, Hall_tab_ptr, direction, ppstmp;
     bool    moving_flag;
     const   uint16_t * lut;
@@ -332,6 +310,8 @@
     int32_t     angle_cnt;
     uint32_t    current_samples[CURRENT_SAMPLES_AVERAGED];  //  Circular buffer where latest current readings get stored
     uint32_t    Hindex[2], tickleon, encoder_error_cnt;
+    uint32_t    RPM, PPS;
+    double      last_V, last_I;
     motor   ()  {}  ;   //  Default constructor
     motor   (PortOut * , FastPWM * , FastPWM * , const uint16_t *, InterruptIn **)  ;
     void    set_V_limit (double)    ;  //  Sets max motor voltage
@@ -369,11 +349,8 @@
     maxI->period_ticks      (MAX_PWM_TICKS + 1);
     maxV->pulsewidth_ticks  (MAX_PWM_TICKS / 20);
     maxI->pulsewidth_ticks  (MAX_PWM_TICKS / 30);
-//    if  (P != PortA && P != PortB)
-//        pc.printf   ("Fatal in 'motor' constructor, Invalid Port\r\n");
-//    else
-//        PortOut Motor_P (P, *mask);     //  PortA for motor A, PortB for motor B
-    mode    = REGENBRAKE;
+    visible_mode    = REGENBRAKE;
+    inner_mode      = REGENBRAKE;
     lut = lutptr;
     Hindex[0] = Hindex[1]  = read_Halls    ();
     ppstmp  = 0;
@@ -384,8 +361,15 @@
     Hall1 = Hall[0];
     Hall2 = Hall[1];
     Hall3 = Hall[2];
+    PPS     = 0;
+    RPM     = 0;
+    last_V = last_I = 0.0;
 }
 
+/**
+void    motor::direction_set   (int dir)  {
+Used to set direction according to mode data from eeprom
+*/
 void    motor::direction_set   (int dir)  {
     if  (dir != 0)
         dir = FORWARD | REVERSE;  //  bits used in eor
@@ -429,7 +413,7 @@
         p = 0.0;
     if  (p > 1.0)
         p = 1.0;
-//    last_pwm = p;
+    last_V = p;     //  for read by diagnostics
     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 to MCP1630 inverted motor pwm as MCP1630 inverts
@@ -442,6 +426,7 @@
         p = 0.0;
     if  (p > 1.0)
         p = 1.0;
+    last_I = p;
     a = (int)(p * MAX_PWM_TICKS);
     if  (a > MAX_PWM_TICKS)
         a = MAX_PWM_TICKS;
@@ -465,6 +450,8 @@
     Hall_tab_ptr++;
     if  (Hall_tab_ptr >= MAIN_LOOP_ITERATION_Hz)
         Hall_tab_ptr = 0;
+    PPS = latest_pulses_per_sec;
+    RPM = (latest_pulses_per_sec * 60) / 24;
     return  latest_pulses_per_sec;
 }
 
@@ -473,15 +460,25 @@
     return  moving_flag;
 }
 
+/**
+bool    motor::set_mode (int m)
+Use to set motor to one mode of HANDBRAKE, FORWARD, REVERSE, REGENBRAKE.
+If this causes change of mode, also sets V and I to zero.
+*/
 bool    motor::set_mode (int m)
 {
     if  ((m != HANDBRAKE) && (m != FORWARD) && (m != REVERSE) && (m !=REGENBRAKE))  {
         pc.printf   ("Error in set_mode, invalid mode %d\r\n", m);
         return  false;
     }
+    if  (visible_mode != m) {   //  Mode change, kill volts and amps to be safe
+        set_V_limit (0.0);
+        set_I_limit (0.0);
+        visible_mode = m;
+    }
     if  (m == FORWARD || m == REVERSE)
         m ^= direction;
-    mode = m;
+    inner_mode = m;     //  idea is to use inner_mode only in lut addressing, keep 'visible_mode' true regardless of setup data in eeprom
     return  true;
 }
 
@@ -503,11 +500,18 @@
         encoder_error_cnt++;
     else
         angle_cnt += delta_theta;
-    *Motor_Port = lut[mode | Hindex[0]];
+    *Motor_Port = lut[inner_mode | Hindex[0]];  //  changed mode to inner_mode 27/04/18
     Hall_total++;
     Hindex[1] = Hindex[0];
 }
 
+    uint32_t    temp_sensor_count = 0;  //  global
+    bool        temp_count_in_progress = false;
+
+void    temp_sensor_isr ()  {   //  got rising edge from LMT01
+    temp_sensor_count++;
+}
+
 void    MAH_isr    ()
 {
     uint32_t x = 0;
@@ -537,7 +541,7 @@
 void    motor::motor_set  ()
 {
     Hindex[0]  = read_Halls    ();
-    *Motor_Port = lut[mode | Hindex[0]];
+    *Motor_Port = lut[inner_mode | Hindex[0]];
 }
 
 void    setVI   (double v, double i)  {
@@ -555,7 +559,24 @@
     MotorB.set_I_limit  (i);
 }
 
-void    sincostest  ()  {
+void    read_RPM    (uint32_t * dest)  {
+    dest[0] = MotorA.RPM;
+    dest[1] = MotorB.RPM;
+}
+
+void    read_PPS    (uint32_t * dest)  {
+    dest[0] = MotorA.PPS;
+    dest[1] = MotorB.PPS;
+}
+
+void    read_last_VI    (double * d)  {   //  only for test from cli
+    d[0]    = MotorA.last_V;
+    d[1]    = MotorA.last_I;
+    d[2]    = MotorB.last_V;
+    d[3]    = MotorB.last_I;
+}
+
+/*void    sincostest  ()  {
     sinv = sin(angle);  //  to set speed and direction of MotorA
     cosv = cos(angle);  //  to set speed and direction of MotorB
         Servos[0]->write  ((sinv + 1.0) / 2.0);
@@ -577,14 +598,25 @@
         cosv = -cosv;
     }
     MotorB.set_V_limit  (0.01 + (cosv / 1.3));
-}
+}*/
 
+/**
+void    AtoD_reader ()  //  Call to here every VOLTAGE_READ_INTERVAL_US    = 50 once loop responds to flag set in isr
+Not part of ISR
+*/
 void    AtoD_reader ()  //  Call to here every VOLTAGE_READ_INTERVAL_US    = 50 once loop responds to flag set in isr
 {
-    static uint32_t i = 0, tab_ptr = 0;
+    static uint32_t i = 0, tab_ptr = 0, local_temperature_count = 0;
 
 //    sincostest  ();
-
+//    uint32_t    temp_sensor_count = 0;  //  global
+//    bool        temp_count_in_progress = false;
+    if  (local_temperature_count == temp_sensor_count)
+        temp_count_in_progress = false;
+    else    {
+        temp_count_in_progress = true;
+        local_temperature_count = temp_sensor_count;
+    }
     if  (MotorA.tickleon)
         MotorA.high_side_off    ();
     if  (MotorB.tickleon)
@@ -620,7 +652,7 @@
     }   //  end of while (AtoD_Semaphore > 0)    {
     if  (MotorA.tickleon)   {
         MotorA.tickleon--;
-        MotorA.motor_set    ();
+        MotorA.motor_set    (); //  Reactivate any high side switches turned off above
     }
     if  (MotorB.tickleon)   {
         MotorB.tickleon--;
@@ -635,25 +667,31 @@
 */
 double  Read_DriverPot  ()
 {
-    return (double) driverpot_reading / 65535.0;     //  Normalise 0.0 <= control pot <= 1.0
+    return ((double) driverpot_reading) / 65536.0;     //  Normalise 0.0 <= control pot <= 1.0
 }
 
 double  Read_BatteryVolts   ()
 {
-    return  (double) volt_reading / 951.0;    //  divisor fiddled to make voltage reading correct !
+    return  ((double) volt_reading) / 951.0;    //  divisor fiddled to make voltage reading correct !
 }
 
-double  read_volts  ()      //  A test function
-{
-    pc.printf   ("pot = %.4f, System Voltage = %.2f\r\n", Read_DriverPot(), Read_BatteryVolts());
-    return  Read_BatteryVolts();
+void    read_supply_vi   (double * val)  {  //  called from cli
+    val[0] = MotorA.I.ave;
+    val[1] = MotorB.I.ave;
+    val[2] = Read_BatteryVolts  ();
 }
 
-void    mode_test   (int mode, double val)  {
+void    mode_set   (int mode, double val)  {   //  called from cli to set fw, re, rb, hb
     MotorA.set_mode (mode);
     MotorB.set_mode (mode);
     if  (mode == REGENBRAKE)    {
-        
+        if  (val > 1.0)
+            val = 1.0;
+        if  (val < 0.0)
+            val = 0.0;
+        val *= 0.9;    //  set upper limit, this is essential
+        val = sqrt  (val);  //  to linearise effect
+        setVI  (val, 1.0);
     }
 }
 
@@ -662,7 +700,7 @@
 extern  bool    wr_24LC64  (int mem_start_addr, char * source, int length)   ;
 extern  bool    rd_24LC64  (int mem_start_addr, char * dest, int length)   ;
 
-struct  motorpairoptions    {   //  This to be user settable in eeprom, 32 bytes
+/*struct  motorpairoptions    {   //  This to be user settable in eeprom, 32 bytes
     uint8_t MotA_dir,   //  0 or 1
             MotB_dir,   //  0 or 1
             gang,       //  0 for separate control (robot mode), 1 for ganged loco bogie mode
@@ -671,27 +709,26 @@
             cmd_source, //  0 Invalid, 1 COM1, 2 COM2, 3 Pot, 4 Servo1, 5 Servo2
             last;
 }   ;
-
+*/
 int I_Am    ()  {   //  Returns boards id number as ASCII char
-    int i = J3;
-    if  (i != 0)
-        i = 1;
-    return  i | '0';
+//    int i = J3;
+//    if  (i != 0)
+//        i = 1;
+//    return  i | '0';
+    return  IAm;
 }
 
 
 int main()
 {
     int eighth_sec_count = 0;
-    uint32_t    Apps, Bpps;
 
     MotA   = 0;     //  Output all 0s to Motor drive ports A and B
     MotB   = 0;
     MotPtr[0] = &MotorA;    //  Pointers to motor class objects
     MotPtr[1] = &MotorB;
-
-//    tryseredge.rise (&seredgerise);
-//    tryseredge.fall (&seredgefall);
+    
+    T1.rise (&temp_sensor_isr);
 
     MAH1.rise   (& MAH_isr);    //  Set up interrupt vectors
     MAH1.fall   (& MAH_isr);
@@ -716,7 +753,6 @@
     Servo1_i.mode   (PullUp);
     Servo2_i.mode   (PullUp);
 
-    pc.printf   ("\tAbandon Hope %d\r\n", LED ? 0 : 1);
     //  Setup system timers to cause periodic interrupts to synchronise and automate volt and current readings, loop repeat rate etc
     tick_vread.attach_us    (&ISR_voltage_reader, VOLTAGE_READ_INTERVAL_US);    //  Start periodic interrupt generator
     loop_timer.attach_us    (&ISR_loop_timer, MAIN_LOOP_REPEAT_TIME_US);    //  Start periodic interrupt generator
@@ -724,39 +760,58 @@
 
     const int TXTBUFSIZ = 36;
     char    buff[TXTBUFSIZ];
-    bool    eerom_detected = false;
     pc.baud     (9600);
     com3.baud   (1200);
     com2.baud   (19200);
     
-    pc.printf   ("RAM test - ");
-    if  (check_24LC64() != 0xa0)  //  searches for i2c devices, returns address of highest found
+    if  (check_24LC64() != 0xa0)  { //  searches for i2c devices, returns address of highest found
         pc.printf   ("Check for 24LC64 eeprom FAILED\r\n");
-    else   //  i2c.write returned 0, think this means device responded with 'ACK', found it anyway
-        eerom_detected = true;
-    if  (eerom_detected)  {
-        bool j, k;
-        pc.printf   ("ok\r\n");
-        static const char ramtst[] = "I found the man sir!";
-        j = wr_24LC64  (0x1240, (char*)ramtst, strlen(ramtst));
-        for (int i = 0; i < TXTBUFSIZ; i++)    buff[i] = 0;     //  Clear buffer
-        //  need a way to check i2c busy - YES implemented ack_poll
-        k = rd_24LC64  (0x1240, buff, strlen(ramtst));
-        pc.printf("Ram test returned [%s], wr ret'd [%s], rd ret'd [%s]\r\n", buff, j ? "true" : "false", k ? "true" : "false");
+        com2.printf   ("Check for 24LC64 eeprom FAILED\r\n");
     }
-    T1 = 0; //  As yet unused pins
-    T2 = 0;
+    else   {        //  Found 24LC64 memory on I2C
+        bool k;
+//        static const char ramtst[] = "I found the man sir!";
+//        j = wr_24LC64  (0x1240, (char*)ramtst, strlen(ramtst));
+//        for (int i = 0; i < TXTBUFSIZ; i++)    buff[i] = 0;     //  Clear buffer
+//        //  need a way to check i2c busy - YES implemented ack_poll
+//        k = rd_24LC64  (0x1240, buff, strlen(ramtst));
+//        pc.printf("Ram test returned [%s], wr ret'd [%s], rd ret'd [%s]\r\n", buff, j ? "true" : "false", k ? "true" : "false");
+//        com2.printf("Ram test returned [%s], wr ret'd [%s], rd ret'd [%s]\r\n", buff, j ? "true" : "false", k ? "true" : "false");
+        k = rd_24LC64   (0, buff, 32);
+//        if  (k)
+//            com2.printf ("Good read from eeprom\r\n");
+        if  (!k)
+            com2.printf ("Error reading from eeprom\r\n");
+
+        int err = 0;
+        for (int i = 0; i < numofopts; i++) {
+            if  ((buff[i] < option_list[i].min) || (buff[i] > option_list[i].max))  {
+                com2.printf ("EEROM error with %s\r\n", option_list[i].t);
+                err++;
+            }
+//            else
+//                com2.printf ("%2x Good %s\r\n", buff[i], option_list[i].t);
+        }
+        IAm = '0';
+        if  (err == 0)  {
+            MotorA.direction_set    (buff[0]);
+            MotorB.direction_set    (buff[1]);
+            IAm = buff[6];
+        }
+           //  Alternative ID 1 to 9
+//        com2.printf ("Alternative ID = 0x%2x\r\n", buff[6]);
+    }
+//    T1 = 0;   Now interruptIn counting pulses from LMT01 temperature sensor
+    T2 = 0; //  T2, T3, T4 As yet unused pins
     T3 = 0;
     T4 = 0;
-    T5 = 0;
+//    T5 = 0; now input from fw/re on remote control box
     T6 = 0;
 //    MotPtr[0]->set_mode (REGENBRAKE);
     MotorA.set_mode (REGENBRAKE);
     MotorB.set_mode (REGENBRAKE);
-    MotorA.set_V_limit  (0.9);
-    MotorB.set_V_limit  (0.9); 
-    MotorA.set_I_limit  (0.5);
-    MotorB.set_I_limit  (0.5);
+    setVI  (0.9, 0.5);
+
     Servos[0] = Servos[1] = NULL;
     //  NOTE The ONLY way to get both servos working properly is to NOT use any if (bla) Servo ervo1(PB_8);
     //  Only works with unconditional inline code
@@ -788,37 +843,32 @@
             break;
     }
     */
-    MotorA.set_mode (FORWARD);
-    MotorB.set_mode (REVERSE);
-    MotorA.set_V_limit  (0.2);
-    MotorB.set_V_limit  (0.2); 
-    MotorA.set_I_limit  (0.5);
-    MotorB.set_I_limit  (0.5);
-
     while   (1) {      //  Loop forever, repeats synchroised by waiting for ticker Interrupt Service Routine to set 'loop_flag' true
         while   (!loop_flag)  {         //  Most of the time is spent in this loop, repeatedly re-checking for commands from pc port
             command_line_interpreter    ()  ;   //  Proceed beyond here once loop_timer ticker ISR has set loop_flag true
             AtoD_reader ();                     //  Performs A to D conversions at rate set by ticker interrupts
         }
         loop_flag = false;              //  Clear flag set by ticker interrupt handler
-        Apps    = MotorA.pulses_per_sec   ();   //  Needed to keep table updated to give reading in Hall transitions per second
-        Bpps    = MotorB.pulses_per_sec   ();
+        MotorA.pulses_per_sec   ();   //  Needed to keep table updated to give reading in Hall transitions per second
+        MotorB.pulses_per_sec   ();   //  Read MotorX.PPS to read pulses per sec or MotorX.RPM to read motor RPM
         T4 = !T4;   //  toggle to hang scope on to verify loop execution
         //  do stuff
         if  (flag_8Hz)  {   //  do slower stuff
             flag_8Hz    = false;
             LED = !LED;                   // Toggle LED on board, should be seen to fast flash
+            WatchDog--;
+            if  (WatchDog == 0) {   //  Deal with WatchDog timer timeout here
+                setVI  (0.0, 0.0);  //  set motor volts and amps to zero
+                com2.printf ("TIMEOUT %2x\r\n", (I_Am() & 0x0f));   //  Potential problem of multiple units reporting at same time overcome by adding board number to WATCHDOG_RELOAD
+            }                       //  End of dealing with WatchDog timer timeout
+            if  (WatchDog < 0)
+                WatchDog = 0;
             eighth_sec_count++;
             if  (eighth_sec_count > 6)    {   //  Send some status info out of serial port every second and a bit or thereabouts
                 eighth_sec_count = 0;
-            MotorA.current_calc ();
+            MotorA.current_calc ();     //  Updates readings in MotorA.I.min, MotorA.I.ave and MotorA.I.max
             MotorB.current_calc ();
-//            Apps += Bpps;   //  to kill compiler warning
-//                pc.printf   ("V=%+.2f, Pot=%+.2f, HA %d, HB %d, IA %d, IB %d, Arpm %d, Brpm %d\r\n", Read_BatteryVolts(), Read_DriverPot(), MotorA.read_Halls  (), MotorB.read_Halls  (), MotorA.I.ave, MotorB.I.ave, (Apps * 60) / 24, (Bpps * 60) / 24);
-                com2.printf   ("V=%+.2f, Pot=%+.2f, HA %d, HB %d, IAmin %d, IAave %d, IAmax %d, IB %d, Arpm %d, Brpm %d\r\n", Read_BatteryVolts(), Read_DriverPot(), MotorA.read_Halls  (), MotorB.read_Halls  (), MotorA.I.min, MotorA.I.ave, MotorA.I.max, MotorB.I.ave, (Apps * 60) / 24, (Bpps * 60) / 24);
-//                pc.printf   ("\tAangle_cnt %d\tAencoder_error_cnt %d", MotorA.angle_cnt, MotorA.encoder_error_cnt);
-//                pc.printf   ("\tBangle_cnt %d\tBencoder_error_cnt %d, J3 %d\r\n", MotorB.angle_cnt, MotorB.encoder_error_cnt, J3 == 0 ? 0 : 1);
-//                com2.printf ("RCI1 pw %d, RCI2 pw %d, 1per %d, 2per %d\r\n", RCI1.pulsewidth(), RCI2.pulsewidth(), RCI1.period(), RCI2.period());
+//                com2.printf   ("V=%+.2f, Pot=%+.2f, HA %d, HB %d, IAmin %d, IAave %d, IAmax %d, IB %d, Arpm %d, Brpm %d\r\n", Read_BatteryVolts(), Read_DriverPot(), MotorA.read_Halls  (), MotorB.read_Halls  (), MotorA.I.min, MotorA.I.ave, MotorA.I.max, MotorB.I.ave, (Apps * 60) / 24, (Bpps * 60) / 24);
             }
         }   //  End of if(flag_8Hz)
     }       //  End of main programme loop