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:
6:f289a49c1eae
Parent:
5:ca86a7848d54
Child:
7:6deaeace9a3e
--- a/main.cpp	Tue May 29 16:36:34 2018 +0000
+++ b/main.cpp	Tue Jun 05 07:19:39 2018 +0000
@@ -6,12 +6,12 @@
 
 /*
 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
+                Also new LMT01 temperature sensor routed to T1 - and rerouted to PC_13 at InterruptIn on T1 (ports A and B I think) not workable
 */
 
 
 /*  STM32F401RE - compile using NUCLEO-F401RE
-//  PROJECT -   Dual Brushless Motor Controller -   Jon Freeman     April 2018.
+//  PROJECT -   Dual Brushless Motor Controller -   Jon Freeman     June 2018.
 
 AnalogIn to read each motor current
 
@@ -28,6 +28,8 @@
 
 
 */
+//#if defined (TARGET_NUCLEO_F446ZE)
+#if defined (TARGET_NUCLEO_F401RE)
 
 //  Hoped to select servo functions from user info stored on EEROM. Too difficult. Do not define servo as in and out
 
@@ -80,7 +82,11 @@
 PortOut MotB    (PortB, PORT_B_MASK);
 
 //  Pin 1   VBAT    NET +3V3
-DigitalIn   J3         (PC_13, PullUp);//  Pin 2   Jumper pulls to GND, R floats Hi
+
+//DigitalIn   J3         (PC_13, PullUp);//  Pin 2   Jumper pulls to GND, R floats Hi
+InterruptIn   Temperature_pin   (PC_13);//  Pin 2   June 2018 - taken for temperature sensor - hard wired to T1 due to wrong thought T1 could be InterruptIn
+
+
 //  Pin 3   PC14-OSC32_IN   NET O32I
 //  Pin 4   PC15-OSC32_OUT  NET O32O
 //  Pin 5   PH0-OSC_IN      NET PH1
@@ -132,7 +138,15 @@
 //BufferedSerial  extra_ser   (PA_11, PA_12);    //  Pins 44, 45  tx, rx to XBee module
 DigitalOut  T2  (PA_11);    //  Pin 44
 // was DigitalOut  T1  (PA_12);    //  Pin 45
-InterruptIn T1  (PA_12);    //  Pin 45 now input counting pulses from LMT01 temperature sensor
+
+
+//InterruptIn T1  (PA_12);    //  Pin 45 now input counting pulses from LMT01 temperature sensor
+//  InterruptIn DOES NOT WORK ON PA_12. Boards are being made, will have to wire link PA12 to PC13
+DigitalIn   T1    (PA_12);
+////InterruptIn T1  (PC_13);    //  Pin 45 now input counting pulses from LMT01 temperature sensor
+
+
+
 //  Pin 46  SWDIO
 //  Pin 47  VSS
 //  Pin 48  VDD
@@ -160,7 +174,9 @@
 //  Pin 64  VDD
 //  SYSTEM CONSTANTS
 
-
+#endif
+#if defined (TARGET_NUCLEO_F446ZE)
+#endif
 /*  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
@@ -171,13 +187,31 @@
 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
+bool        temp_sensor_exists = false;
+char        mode_bytes[36];
 
+uint32_t    temp_sensor_count = 0,  //  incremented by every rising edge from LMT01
+            last_temp_count = 0;  //  global updated approx every 100ms after each LMT01 conversion completes
+//    struct  single_bogie_options    bogie;    
 /*  End of Global variable declarations */
 
 Ticker  tick_vread;     //  Device to cause periodic interrupts, used to time voltage readings etc
 Ticker  loop_timer;     //  Device to cause periodic interrupts, used to sync iterations of main programme loop
+Ticker  temperature_find_ticker;
+Timer   temperature_timer;
 
 //  Interrupt Service Routines
+void    ISR_temperature_find_ticker ()  {   //  every 960 us, i.e. slightly faster than once per milli sec
+    static  bool    readflag = false;
+    int t = temperature_timer.read_ms   ();
+    if  ((t == 5) && (!readflag))    {
+        last_temp_count = temp_sensor_count;
+        temp_sensor_count = 0;
+        readflag = true;
+    }
+    if  (t == 6)
+        readflag = false;
+}
 
 /** void    ISR_loop_timer  ()
 *   This ISR responds to Ticker interrupts at a rate of (probably) 32 times per second (check from constant declarations above)
@@ -240,7 +274,7 @@
     return  rx_active;
 }
 
-void    RControl_In::rise    ()
+void    RControl_In::rise    ()     //  These may not work as use of PortB as port may bugger InterruptIn use
 {
     t.stop   ();
     period_us = t.read_us    ();
@@ -505,11 +539,14 @@
     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
+void    temp_sensor_isr ()  {   //  got rising edge from LMT01. ALMOST CERTAIN this misses some
+    int t = temperature_timer.read_us   (); //  Must be being overrun by something, most likely culprit A-D reading ?
+    temperature_timer.reset ();
     temp_sensor_count++;
+    if  (t > 18)            //  Yes proved some interrupts get missed, this fixes temperature reading
+        temp_sensor_count++;
+//    T2 = !T2;   //  scope hanger
 }
 
 void    MAH_isr    ()
@@ -576,29 +613,6 @@
     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);
-        Servos[1]->write  ((cosv + 1.0) / 2.0);
-    angle += angle_step;
-    if  (angle > TWOPI)
-        angle -= TWOPI;
-    if  (sinv > 0.0)
-        MotorA.set_mode (FORWARD);
-    else    {
-        MotorA.set_mode (REVERSE);
-        sinv = -sinv;
-    }
-    MotorA.set_V_limit  (0.01 + (sinv / 1.3));
-    if  (cosv > 0.0)
-        MotorB.set_mode (FORWARD);
-    else    {
-        MotorB.set_mode (REVERSE);
-        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
@@ -606,17 +620,8 @@
 */
 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, local_temperature_count = 0;
+    static uint32_t i = 0, tab_ptr = 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)
@@ -711,10 +716,6 @@
 }   ;
 */
 int I_Am    ()  {   //  Returns boards id number as ASCII char
-//    int i = J3;
-//    if  (i != 0)
-//        i = 1;
-//    return  i | '0';
     return  IAm;
 }
 
@@ -728,7 +729,8 @@
     MotPtr[0] = &MotorA;    //  Pointers to motor class objects
     MotPtr[1] = &MotorB;
     
-    T1.rise (&temp_sensor_isr);
+    Temperature_pin.fall (&temp_sensor_isr);
+    Temperature_pin.mode (PullUp);
 
     MAH1.rise   (& MAH_isr);    //  Set up interrupt vectors
     MAH1.fall   (& MAH_isr);
@@ -756,14 +758,16 @@
     //  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
+    temperature_find_ticker.attach_us   (&ISR_temperature_find_ticker, 960);
     //  Done setting up system interrupt timers
+    temperature_timer.start ();
 
-    const int TXTBUFSIZ = 36;
-    char    buff[TXTBUFSIZ];
+//    const   int TXTBUFSIZ = 36;
+//    char    buff[TXTBUFSIZ];
     pc.baud     (9600);
     com3.baud   (1200);
     com2.baud   (19200);
-    
+
     if  (check_24LC64() != 0xa0)  { //  searches for i2c devices, returns address of highest found
         pc.printf   ("Check for 24LC64 eeprom FAILED\r\n");
         com2.printf   ("Check for 24LC64 eeprom FAILED\r\n");
@@ -777,15 +781,15 @@
 //        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);
+        k = rd_24LC64   (0, mode_bytes, 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))  {
+        for (int i = 0; i < numof_eeprom_options; i++) {
+            if  ((mode_bytes[i] < option_list[i].min) || (mode_bytes[i] > option_list[i].max))  {
                 com2.printf ("EEROM error with %s\r\n", option_list[i].t);
                 err++;
             }
@@ -794,14 +798,14 @@
         }
         IAm = '0';
         if  (err == 0)  {
-            MotorA.direction_set    (buff[0]);
-            MotorB.direction_set    (buff[1]);
-            IAm = buff[6];
+            MotorA.direction_set    (mode_bytes[MOTADIR]);
+            MotorB.direction_set    (mode_bytes[MOTBDIR]);
+            IAm = mode_bytes[ID];
         }
            //  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
+//    T1 = 0;   Now WRONGLY hoped to be InterruptIn counting pulses from LMT01 temperature sensor
     T2 = 0; //  T2, T3, T4 As yet unused pins
     T3 = 0;
     T4 = 0;
@@ -821,6 +825,10 @@
     Servos[0] = & Servo1;
     Servo   Servo2  (PB_9)  ;
     Servos[1] = & Servo2;
+    
+    pc.printf   ("last_temp_count = %d\r\n", last_temp_count);  //  Has had time to do at least 1 conversion
+    if  ((last_temp_count > 160) && (last_temp_count < 2400))   //  in range -40 to +100 degree C
+        temp_sensor_exists  = true;
 /*
     //  Setup Complete ! Can now start main control forever loop.
     //  March 16th 2018 thoughts !!!
@@ -843,6 +851,7 @@
             break;
     }
     */
+    pc.printf   ("Ready to go!, wheel gear in position %d\r\n", WHEELGEAR);
     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
@@ -866,8 +875,14 @@
             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 ();     //  Updates readings in MotorA.I.min, MotorA.I.ave and MotorA.I.max
-            MotorB.current_calc ();
+                MotorA.current_calc ();     //  Updates readings in MotorA.I.min, MotorA.I.ave and MotorA.I.max
+                MotorB.current_calc ();
+                if  (temp_sensor_exists)    {
+                    double  tmprt = (double) last_temp_count;
+                    tmprt /= 16.0;
+                    tmprt -= 50.0;
+                    pc.printf   ("Temp %.2f\r\n", tmprt);
+                }
 //                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)