Make LPC1768 pinmapping not specific to Re-ARM (#8063)
* Merging early because of build failures. See #8105 * Make LPC1768 pinmapping not specific to Re-ARM * Add HAL_PIN_TYPE and LPC1768 pin features * M43 Updates * Move pin map into pinsDebug_LPC1768.h * Incorporate comments and M226 * Fix persistent store compilation issues * Update pin features * Update MKS SBASE pins * Use native LPC1768 pin numbers in M42, M43, and M226
This commit is contained in:
		@@ -29,16 +29,17 @@
 | 
			
		||||
 */
 | 
			
		||||
void GcodeSuite::M226() {
 | 
			
		||||
  if (parser.seen('P')) {
 | 
			
		||||
    const int pin_number = parser.value_int(),
 | 
			
		||||
    const int pin_number = PARSED_PIN_INDEX('P', 0),
 | 
			
		||||
              pin_state = parser.intval('S', -1); // required pin state - default is inverted
 | 
			
		||||
    const pin_t pin = GET_PIN_MAP_PIN(pin_number);
 | 
			
		||||
 | 
			
		||||
    if (WITHIN(pin_state, -1, 1) && pin_number > -1 && !pin_is_protected(pin_number)) {
 | 
			
		||||
    if (WITHIN(pin_state, -1, 1) && pin > -1 && !pin_is_protected(pin)) {
 | 
			
		||||
 | 
			
		||||
      int target = LOW;
 | 
			
		||||
 | 
			
		||||
      stepper.synchronize();
 | 
			
		||||
 | 
			
		||||
      pinMode(pin_number, INPUT);
 | 
			
		||||
      pinMode(pin, INPUT);
 | 
			
		||||
      switch (pin_state) {
 | 
			
		||||
        case 1:
 | 
			
		||||
          target = HIGH;
 | 
			
		||||
@@ -47,12 +48,12 @@ void GcodeSuite::M226() {
 | 
			
		||||
          target = LOW;
 | 
			
		||||
          break;
 | 
			
		||||
        case -1:
 | 
			
		||||
          target = !digitalRead(pin_number);
 | 
			
		||||
          target = !digitalRead(pin);
 | 
			
		||||
          break;
 | 
			
		||||
      }
 | 
			
		||||
 | 
			
		||||
      while (digitalRead(pin_number) != target) idle();
 | 
			
		||||
      while (digitalRead(pin) != target) idle();
 | 
			
		||||
 | 
			
		||||
    } // pin_state -1 0 1 && pin_number > -1
 | 
			
		||||
    } // pin_state -1 0 1 && pin > -1
 | 
			
		||||
  } // parser.seen('P')
 | 
			
		||||
}
 | 
			
		||||
 
 | 
			
		||||
@@ -34,21 +34,22 @@ void GcodeSuite::M42() {
 | 
			
		||||
  if (!parser.seenval('S')) return;
 | 
			
		||||
  const byte pin_status = parser.value_byte();
 | 
			
		||||
 | 
			
		||||
  const int pin_number = parser.intval('P', LED_PIN);
 | 
			
		||||
  int pin_number = PARSED_PIN_INDEX('P', GET_PIN_MAP_INDEX(LED_PIN));
 | 
			
		||||
  if (pin_number < 0) return;
 | 
			
		||||
 | 
			
		||||
  if (pin_is_protected(pin_number)) {
 | 
			
		||||
  const pin_t pin = GET_PIN_MAP_PIN(pin_number);
 | 
			
		||||
  if (pin_is_protected(pin)) {
 | 
			
		||||
    SERIAL_ERROR_START();
 | 
			
		||||
    SERIAL_ERRORLNPGM(MSG_ERR_PROTECTED_PIN);
 | 
			
		||||
    return;
 | 
			
		||||
  }
 | 
			
		||||
 | 
			
		||||
  pinMode(pin_number, OUTPUT);
 | 
			
		||||
  digitalWrite(pin_number, pin_status);
 | 
			
		||||
  analogWrite(pin_number, pin_status);
 | 
			
		||||
  pinMode(pin, OUTPUT);
 | 
			
		||||
  digitalWrite(pin, pin_status);
 | 
			
		||||
  analogWrite(pin, pin_status);
 | 
			
		||||
 | 
			
		||||
  #if FAN_COUNT > 0
 | 
			
		||||
    switch (pin_number) {
 | 
			
		||||
    switch (pin) {
 | 
			
		||||
      #if HAS_FAN0
 | 
			
		||||
        case FAN_PIN: fanSpeeds[0] = pin_status; break;
 | 
			
		||||
      #endif
 | 
			
		||||
 
 | 
			
		||||
		Reference in New Issue
	
	Block a user