Browse Source

Merge pull request #5118 from thinkyhead/rc_expanded_M43

Enhancements to M43 pins debugging
Scott Lahteine 7 years ago
parent
commit
fa6bf12697
4 changed files with 859 additions and 236 deletions
  1. 34
    8
      Marlin/Marlin_main.cpp
  2. 729
    224
      Marlin/pinsDebug.h
  3. 2
    2
      Marlin/pins_A4JP.h
  4. 94
    2
      Marlin/temperature.cpp

+ 34
- 8
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,20 +4676,43 @@ inline void gcode_M42() {
4675 4676
   /**
4676 4677
    * M43: Pin report and debug
4677 4678
    *
4678
-   *      P<pin> Will read/watch a single pin
4679
-   *      W      Watch pins for changes until reboot
4679
+   *      E<bool> Enable / disable background endstop monitoring
4680
+   *               - Machine continues to operate
4681
+   *               - Reports changes to endstops
4682
+   *               - Toggles LED when an endstop changes
4683
+   *
4684
+   *   or
4685
+   *
4686
+   *      P<pin>  Pin to read or watch. If omitted, read/watch all pins.
4687
+   *      W<bool> Watch pins -reporting changes- until reset, click, or M108.
4688
+   *      I<bool> Flag to ignore Marlin's pin protection.
4689
+   *
4680 4690
    */
4681 4691
   inline void gcode_M43() {
4682
-    int first_pin = 0, last_pin = DIO_COUNT - 1;
4692
+
4693
+    // Enable or disable endstop monitoring
4694
+    if (code_seen('E')) {
4695
+      endstop_monitor_flag = code_value_bool();
4696
+      SERIAL_PROTOCOLPGM("endstop monitor ");
4697
+      SERIAL_PROTOCOL(endstop_monitor_flag ? "en" : "dis");
4698
+      SERIAL_PROTOCOLLNPGM("abled");
4699
+      return;
4700
+    }
4701
+
4702
+    // Get the range of pins to test or watch
4703
+    int first_pin = 0, last_pin = NUM_DIGITAL_PINS - 1;
4683 4704
     if (code_seen('P')) {
4684 4705
       first_pin = last_pin = code_value_byte();
4685
-      if (first_pin > DIO_COUNT - 1) return;
4706
+      if (first_pin > NUM_DIGITAL_PINS - 1) return;
4686 4707
     }
4687 4708
 
4709
+    bool ignore_protection = code_seen('I') ? code_value_bool() : false;
4710
+
4711
+    // Watch until click, M108, or reset
4688 4712
     if (code_seen('W') && code_value_bool()) { // watch digital pins
4689 4713
       byte pin_state[last_pin - first_pin + 1];
4690 4714
       for (int8_t pin = first_pin; pin <= last_pin; pin++) {
4691
-        if (pin_is_protected(pin)) continue;
4715
+        if (pin_is_protected(pin) && !ignore_protection) continue;
4692 4716
         pinMode(pin, INPUT_PULLUP);
4693 4717
         // if (IS_ANALOG(pin))
4694 4718
         //   pin_state[pin - first_pin] = analogRead(pin - analogInputToDigitalPin(0)); // int16_t pin_state[...]
@@ -4720,10 +4744,12 @@ inline void gcode_M42() {
4720 4744
 
4721 4745
         safe_delay(500);
4722 4746
       }
4747
+      return;
4723 4748
     }
4724
-    else // single pins report
4725
-      for (int8_t pin = first_pin; pin <= last_pin; pin++)
4726
-        report_pin_state(pin);
4749
+
4750
+    // Report current state of selected pin(s)
4751
+    for (uint8_t pin = first_pin; pin <= last_pin; pin++)
4752
+      report_pin_state_extended(pin, ignore_protection);
4727 4753
   }
4728 4754
 
4729 4755
 #endif // PINS_DEBUGGING

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


+ 2
- 2
Marlin/pins_A4JP.h View File

@@ -115,8 +115,8 @@
115 115
 #define HEATER_BED_PIN       3
116 116
 
117 117
 #define FAN_PIN              8
118
-#define FAN0_PIN             6
119
-#define FAN1_PIN             2
118
+#define FAN1_PIN             6
119
+#define FAN2_PIN             2
120 120
 
121 121
 //
122 122
 // Misc. Functions

+ 94
- 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
+    uint16_t current_endstop_bits_local = 0;
1411
+    #if HAS_X_MIN
1412
+      if (READ(X_MIN_PIN)) SBI(current_endstop_bits_local, X_MIN);
1413
+    #endif
1414
+    #if HAS_X_MAX
1415
+      if (READ(X_MAX_PIN)) SBI(current_endstop_bits_local, X_MAX);
1416
+    #endif
1417
+    #if HAS_Y_MIN
1418
+      if (READ(Y_MIN_PIN)) SBI(current_endstop_bits_local, Y_MIN);
1419
+    #endif
1420
+    #if HAS_Y_MAX
1421
+      if (READ(Y_MAX_PIN)) SBI(current_endstop_bits_local, Y_MAX);
1422
+    #endif
1423
+    #if HAS_Z_MIN
1424
+      if (READ(Z_MIN_PIN)) SBI(current_endstop_bits_local, Z_MIN);
1425
+    #endif
1426
+    #if HAS_Z_MAX
1427
+      if (READ(Z_MAX_PIN)) SBI(current_endstop_bits_local, Z_MAX);
1428
+    #endif
1429
+    #if HAS_Z_MIN_PROBE_PIN
1430
+      if (READ(Z_MIN_PROBE_PIN)) SBI(current_endstop_bits_local, Z_MIN_PROBE);
1431
+    #endif
1432
+    #if HAS_Z2_MIN
1433
+      if (READ(Z2_MIN_PIN)) SBI(current_endstop_bits_local, Z2_MIN);
1434
+    #endif
1435
+    #if HAS_Z2_MAX
1436
+      if (READ(Z2_MAX_PIN)) SBI(current_endstop_bits_local, Z2_MAX);
1437
+    #endif
1438
+
1439
+    uint16_t endstop_change = current_endstop_bits_local ^ old_endstop_bits_local;
1440
+
1441
+    if (endstop_change) {
1442
+      #if HAS_X_MIN
1443
+        if (TEST(endstop_change, X_MIN)) SERIAL_PROTOCOLPAIR("X_MIN:", !!TEST(current_endstop_bits_local, X_MIN));
1444
+      #endif
1445
+      #if HAS_X_MAX
1446
+        if (TEST(endstop_change, X_MAX)) SERIAL_PROTOCOLPAIR("  X_MAX:", !!TEST(current_endstop_bits_local, X_MAX));
1447
+      #endif
1448
+      #if HAS_Y_MIN
1449
+        if (TEST(endstop_change, Y_MIN)) SERIAL_PROTOCOLPAIR("  Y_MIN:", !!TEST(current_endstop_bits_local, Y_MIN));
1450
+      #endif
1451
+      #if HAS_Y_MAX
1452
+        if (TEST(endstop_change, Y_MAX)) SERIAL_PROTOCOLPAIR("  Y_MAX:", !!TEST(current_endstop_bits_local, Y_MAX));
1453
+      #endif
1454
+      #if HAS_Z_MIN
1455
+        if (TEST(endstop_change, Z_MIN)) SERIAL_PROTOCOLPAIR("  Z_MIN:", !!TEST(current_endstop_bits_local, Z_MIN));
1456
+      #endif
1457
+      #if HAS_Z_MAX
1458
+        if (TEST(endstop_change, Z_MAX)) SERIAL_PROTOCOLPAIR("  Z_MAX:", !!TEST(current_endstop_bits_local, Z_MAX));
1459
+      #endif
1460
+      #if HAS_Z_MIN_PROBE_PIN
1461
+        if (TEST(endstop_change, Z_MIN_PROBE)) SERIAL_PROTOCOLPAIR("  PROBE:", !!TEST(current_endstop_bits_local, Z_MIN_PROBE));
1462
+      #endif
1463
+      #if HAS_Z2_MIN
1464
+        if (TEST(endstop_change, Z2_MIN)) SERIAL_PROTOCOLPAIR("  Z2_MIN:", !!TEST(current_endstop_bits_local, Z2_MIN));
1465
+      #endif
1466
+      #if HAS_Z2_MAX
1467
+        if (TEST(endstop_change, Z2_MAX)) SERIAL_PROTOCOLPAIR("  Z2_MAX:", !!TEST(current_endstop_bits_local, Z2_MAX));
1468
+      #endif
1469
+      SERIAL_PROTOCOLPGM("\n\n");
1470
+      analogWrite(LED_PIN, local_LED_status);
1471
+      local_LED_status ^= 255;
1472
+      old_endstop_bits_local = current_endstop_bits_local;
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,15 @@ void Temperature::isr() {
1848 1929
       }
1849 1930
     }
1850 1931
   #endif //BABYSTEPPING
1932
+
1933
+  #if ENABLED(PINS_DEBUGGING)
1934
+    extern bool endstop_monitor_flag;
1935
+    // run the endstop monitor at 15Hz
1936
+    static uint8_t endstop_monitor_count = 16;  // offset this check from the others
1937
+    if (endstop_monitor_flag) {
1938
+      endstop_monitor_count += _BV(1);  //  15 Hz
1939
+      endstop_monitor_count &= 0x7F;
1940
+      if (!endstop_monitor_count) endstop_monitor();  // report changes in endstop status
1941
+    }
1942
+  #endif
1851 1943
 }

Loading…
Cancel
Save