Browse Source

Add endstop monitor & make pins report pretty

Bob-the-Kuhn 7 years ago
parent
commit
c7f1f0dae6
3 changed files with 982 additions and 219 deletions
  1. 17
    3
      Marlin/Marlin_main.cpp
  2. 874
    214
      Marlin/pinsDebug.h
  3. 91
    2
      Marlin/temperature.cpp

+ 17
- 3
Marlin/Marlin_main.cpp View File

@@ -148,6 +148,7 @@
148 148
  *        The '#' is necessary when calling from within sd files, as it stops buffer prereading
149 149
  * M33  - Get the longname version of a path. (Requires LONG_FILENAME_HOST_SUPPORT)
150 150
  * M42  - Change pin status via gcode: M42 P<pin> S<value>. LED pin assumed if P is omitted.
151
+ * M43  - Monitor pins & report changes - report active pins
151 152
  * M48  - Measure Z Probe repeatability: M48 P<points> X<pos> Y<pos> V<level> E<engage> L<legs>. (Requires Z_MIN_PROBE_REPEATABILITY_TEST)
152 153
  * M75  - Start the print job timer.
153 154
  * M76  - Pause the print job timer.
@@ -4675,8 +4676,14 @@ inline void gcode_M42() {
4675 4676
   /**
4676 4677
    * M43: Pin report and debug
4677 4678
    *
4679
+   *      pin report if just M43 with no codes
4678 4680
    *      P<pin> Will read/watch a single pin
4679 4681
    *      W      Watch pins for changes until reboot
4682
+   *      E      toggles endstop monitor
4683
+   *               reports changes to endstops
4684
+   *               toggles LED when endstop changes
4685
+   *               background function (machine continues to operate as normal)
4686
+   *
4680 4687
    */
4681 4688
   inline void gcode_M43() {
4682 4689
     int first_pin = 0, last_pin = DIO_COUNT - 1;
@@ -4721,9 +4728,16 @@ inline void gcode_M42() {
4721 4728
         safe_delay(500);
4722 4729
       }
4723 4730
     }
4724
-    else // single pins report
4725
-      for (int8_t pin = first_pin; pin <= last_pin; pin++)
4726
-        report_pin_state(pin);
4731
+    if ( !(code_seen('P') || code_seen('W') || code_seen('E')))   // single pins report
4732
+      for (uint8_t pin = first_pin; pin <= last_pin; pin++)
4733
+        report_pin_state_extended(pin, code_seen('I') );        // "hidden" option to ignore protected list
4734
+    
4735
+    if (code_seen('E')) {
4736
+      endstop_monitor_flag ^= true;
4737
+      SERIAL_PROTOCOLPGM("endstop monitor ");
4738
+      SERIAL_PROTOCOL(endstop_monitor_flag ? "en" : "dis");
4739
+      SERIAL_PROTOCOLLNPGM("abled");
4740
+    }    
4727 4741
   }
4728 4742
 
4729 4743
 #endif // PINS_DEBUGGING

+ 874
- 214
Marlin/pinsDebug.h
File diff suppressed because it is too large
View File


+ 91
- 2
Marlin/temperature.cpp View File

@@ -462,12 +462,12 @@ int Temperature::getHeaterPower(int heater) {
462 462
       AUTO_3_IS_0 ? 0 : AUTO_3_IS_1 ? 1 : AUTO_3_IS_2 ? 2 : 3
463 463
     };
464 464
     uint8_t fanState = 0;
465
- 
465
+
466 466
     HOTEND_LOOP() {
467 467
       if (current_temperature[e] > EXTRUDER_AUTO_FAN_TEMPERATURE)
468 468
         SBI(fanState, fanBit[e]);
469 469
     }
470
- 
470
+
471 471
     uint8_t fanDone = 0;
472 472
     for (uint8_t f = 0; f < COUNT(fanPin); f++) {
473 473
       int8_t pin = fanPin[f];
@@ -1393,6 +1393,87 @@ void Temperature::set_current_temp_raw() {
1393 1393
   temp_meas_ready = true;
1394 1394
 }
1395 1395
 
1396
+#if ENABLED(PINS_DEBUGGING)
1397
+  /**
1398
+   * monitors endstops & Z probe for changes
1399
+   *
1400
+   * If a change is detected then the LED is toggled and
1401
+   * a message is sent out the serial port
1402
+   *
1403
+   * Yes, we could miss a rapid back & forth change but
1404
+   * that won't matter because this is all manual.
1405
+   *
1406
+   */
1407
+  void endstop_monitor() {
1408
+    static uint16_t old_endstop_bits_local = 0;
1409
+    static uint8_t local_LED_status = 0;
1410
+    if (endstop_monitor_flag) {
1411
+      uint16_t current_endstop_bits_local = 0;
1412
+      #if HAS_X_MIN
1413
+        if (READ(X_MIN_PIN)) current_endstop_bits_local |= _BV(X_MIN);
1414
+        if ((current_endstop_bits_local ^ old_endstop_bits_local) & _BV(X_MIN)) {
1415
+          SERIAL_PROTOCOLPAIR("X_MIN: ", (current_endstop_bits_local & _BV(X_MIN)) ? 1 : 0);
1416
+        }
1417
+      #endif
1418
+      #if HAS_X_MAX
1419
+        if (READ(X_MAX_PIN)) current_endstop_bits_local |= _BV(X_MAX);
1420
+        if ((current_endstop_bits_local ^ old_endstop_bits_local) & _BV(X_MAX)) {
1421
+          SERIAL_PROTOCOLPAIR("   X_MAX: ", (current_endstop_bits_local & _BV(X_MAX)) ? 1 : 0);
1422
+        }
1423
+      #endif
1424
+      #if HAS_Y_MIN
1425
+        if (READ(Y_MIN_PIN)) current_endstop_bits_local |= _BV(Y_MIN);
1426
+        if ((current_endstop_bits_local ^ old_endstop_bits_local) & _BV(Y_MIN)) {
1427
+          SERIAL_PROTOCOLPAIR("   Y_MIN: ", (current_endstop_bits_local & _BV(Y_MIN)) ? 1 : 0);
1428
+        }
1429
+      #endif
1430
+      #if HAS_Y_MAX
1431
+        if (READ(Y_MAX_PIN)) current_endstop_bits_local |= _BV(Y_MAX);
1432
+        if ((current_endstop_bits_local ^ old_endstop_bits_local) & _BV(Y_MAX)) {
1433
+          SERIAL_PROTOCOLPAIR("   Y_MAX: ", (current_endstop_bits_local & _BV(Y_MAX)) ? 1 : 0);
1434
+        }
1435
+      #endif
1436
+      #if HAS_Z_MIN
1437
+        if (READ(Z_MIN_PIN)) current_endstop_bits_local |= _BV(Z_MIN);
1438
+        if ((current_endstop_bits_local ^ old_endstop_bits_local) & _BV(Z_MIN)) {
1439
+          SERIAL_PROTOCOLPAIR("   Z_MIN: ", (current_endstop_bits_local & _BV(Z_MIN)) ? 1 : 0);
1440
+        }
1441
+      #endif
1442
+      #if HAS_Z_MAX
1443
+        if (READ(Z_MAX_PIN)) current_endstop_bits_local |= _BV(Z_MAX);
1444
+        if ((current_endstop_bits_local ^ old_endstop_bits_local) & _BV(Z_MAX)) {
1445
+          SERIAL_PROTOCOLPAIR("   Z_MAX: ", (current_endstop_bits_local & _BV(Z_MAX)) ? 1 : 0);
1446
+        }
1447
+      #endif
1448
+      #if HAS_Z_MIN_PROBE_PIN
1449
+        if (READ(Z_MIN_PROBE_PIN)) current_endstop_bits_local |= _BV(Z_MIN_PROBE);
1450
+        if ((current_endstop_bits_local ^ old_endstop_bits_local) & _BV(Z_MIN_PROBE)) {
1451
+          SERIAL_PROTOCOLPAIR("   PROBE: ", (current_endstop_bits_local & _BV(Z_MIN_PROBE)) ? 1 : 0);
1452
+        }
1453
+      #endif
1454
+      #if HAS_Z2_MIN
1455
+        if (READ(Z2_MIN_PIN)) current_endstop_bits_local |= _BV(Z2_MIN);
1456
+        if ((current_endstop_bits_local ^ old_endstop_bits_local) & _BV(Z2_MIN)) {
1457
+          SERIAL_PROTOCOLPAIR("   Z2_MIN: ", (current_endstop_bits_local & _BV(Z2_MIN)) ? 1 : 0);
1458
+        }
1459
+      #endif
1460
+      #if HAS_Z2_MAX
1461
+        if (READ(Z2_MAX_PIN)) current_endstop_bits_local |= _BV(Z2_MAX);
1462
+        if ((current_endstop_bits_local ^ old_endstop_bits_local) & _BV(Z2_MAX)) {
1463
+          SERIAL_PROTOCOLPAIR("   Z2_MAX: ", (current_endstop_bits_local & _BV(Z2_MAX)) ? 1 : 0);
1464
+        }
1465
+      #endif
1466
+
1467
+      if (current_endstop_bits_local != old_endstop_bits_local) {
1468
+        analogWrite(LED_PIN, local_LED_status );                // toggle LED
1469
+        SERIAL_PROTOCOLPGM("\n\n");                             // make it easy to see the message
1470
+        old_endstop_bits_local = current_endstop_bits_local ;   // get ready for next change
1471
+        local_LED_status  = local_LED_status ? 0 : 255;
1472
+      }
1473
+    }
1474
+  }
1475
+#endif // PINS_DEBUGGING
1476
+
1396 1477
 /**
1397 1478
  * Timer 0 is shared with millies so don't change the prescaler.
1398 1479
  *
@@ -1848,4 +1929,12 @@ void Temperature::isr() {
1848 1929
       }
1849 1930
     }
1850 1931
   #endif //BABYSTEPPING
1932
+  #if ENABLED(PINS_DEBUGGING)
1933
+    extern bool endstop_monitor_flag;
1934
+    // run the endstop monitor at 15Hz
1935
+    static uint8_t endstop_monitor_count = 16;  // offset this check from the others
1936
+    endstop_monitor_count += _BV(1);  //  15 Hz
1937
+    endstop_monitor_count &= 0x7F;
1938
+    if (endstop_monitor_count == 0) endstop_monitor();  // report changes in endstop status
1939
+  #endif
1851 1940
 }

Loading…
Cancel
Save