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:
@ -36,11 +36,12 @@
|
||||
inline void toggle_pins() {
|
||||
const bool I_flag = parser.boolval('I');
|
||||
const int repeat = parser.intval('R', 1),
|
||||
start = parser.intval('S'),
|
||||
end = parser.intval('E', NUM_DIGITAL_PINS - 1),
|
||||
start = PARSED_PIN_INDEX('S', 0),
|
||||
end = PARSED_PIN_INDEX('E', NUM_DIGITAL_PINS - 1),
|
||||
wait = parser.intval('W', 500);
|
||||
|
||||
for (uint8_t pin = start; pin <= end; pin++) {
|
||||
for (uint8_t i = start; i <= end; i++) {
|
||||
pin_t pin = GET_PIN_MAP_PIN(i);
|
||||
//report_pin_state_extended(pin, I_flag, false);
|
||||
if (!VALID_PIN(pin)) continue;
|
||||
if (!I_flag && pin_is_protected(pin)) {
|
||||
@ -258,7 +259,7 @@ void GcodeSuite::M43() {
|
||||
}
|
||||
|
||||
// Get the range of pins to test or watch
|
||||
const uint8_t first_pin = parser.byteval('P'),
|
||||
const uint8_t first_pin = PARSED_PIN_INDEX('P', 0),
|
||||
last_pin = parser.seenval('P') ? first_pin : NUM_DIGITAL_PINS - 1;
|
||||
|
||||
if (first_pin > last_pin) return;
|
||||
@ -269,7 +270,8 @@ void GcodeSuite::M43() {
|
||||
if (parser.boolval('W')) {
|
||||
SERIAL_PROTOCOLLNPGM("Watching pins");
|
||||
uint8_t pin_state[last_pin - first_pin + 1];
|
||||
for (int8_t pin = first_pin; pin <= last_pin; pin++) {
|
||||
for (uint8_t i = first_pin; i <= last_pin; i++) {
|
||||
pin_t pin = GET_PIN_MAP_PIN(i);
|
||||
if (!VALID_PIN(pin)) continue;
|
||||
if (pin_is_protected(pin) && !ignore_protection) continue;
|
||||
pinMode(pin, INPUT_PULLUP);
|
||||
@ -279,7 +281,7 @@ void GcodeSuite::M43() {
|
||||
pin_state[pin - first_pin] = analogRead(DIGITAL_PIN_TO_ANALOG_PIN(pin)); // int16_t pin_state[...]
|
||||
else
|
||||
//*/
|
||||
pin_state[pin - first_pin] = digitalRead(pin);
|
||||
pin_state[i - first_pin] = digitalRead(pin);
|
||||
}
|
||||
|
||||
#if HAS_RESUME_CONTINUE
|
||||
@ -288,7 +290,8 @@ void GcodeSuite::M43() {
|
||||
#endif
|
||||
|
||||
for (;;) {
|
||||
for (int8_t pin = first_pin; pin <= last_pin; pin++) {
|
||||
for (uint8_t i = first_pin; i <= last_pin; i++) {
|
||||
pin_t pin = GET_PIN_MAP_PIN(i);
|
||||
if (!VALID_PIN(pin)) continue;
|
||||
if (pin_is_protected(pin) && !ignore_protection) continue;
|
||||
const byte val =
|
||||
@ -298,9 +301,9 @@ void GcodeSuite::M43() {
|
||||
:
|
||||
//*/
|
||||
digitalRead(pin);
|
||||
if (val != pin_state[pin - first_pin]) {
|
||||
if (val != pin_state[i - first_pin]) {
|
||||
report_pin_state_extended(pin, ignore_protection, false);
|
||||
pin_state[pin - first_pin] = val;
|
||||
pin_state[i - first_pin] = val;
|
||||
}
|
||||
}
|
||||
|
||||
@ -317,8 +320,10 @@ void GcodeSuite::M43() {
|
||||
}
|
||||
|
||||
// Report current state of selected pin(s)
|
||||
for (uint8_t pin = first_pin; pin <= last_pin; pin++)
|
||||
for (uint8_t i = first_pin; i <= last_pin; i++) {
|
||||
pin_t pin = GET_PIN_MAP_PIN(i);
|
||||
if (VALID_PIN(pin)) report_pin_state_extended(pin, ignore_protection, true);
|
||||
}
|
||||
}
|
||||
|
||||
#endif // PINS_DEBUGGING
|
||||
|
@ -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
|
||||
|
@ -293,15 +293,16 @@ public:
|
||||
void unknown_command_error();
|
||||
|
||||
// Provide simple value accessors with default option
|
||||
FORCE_INLINE static float floatval(const char c, const float dval=0.0) { return seenval(c) ? value_float() : dval; }
|
||||
FORCE_INLINE static bool boolval(const char c) { return seenval(c) ? value_bool() : seen(c); }
|
||||
FORCE_INLINE static uint8_t byteval(const char c, const uint8_t dval=0) { return seenval(c) ? value_byte() : dval; }
|
||||
FORCE_INLINE static int16_t intval(const char c, const int16_t dval=0) { return seenval(c) ? value_int() : dval; }
|
||||
FORCE_INLINE static uint16_t ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort() : dval; }
|
||||
FORCE_INLINE static int32_t longval(const char c, const int32_t dval=0) { return seenval(c) ? value_long() : dval; }
|
||||
FORCE_INLINE static uint32_t ulongval(const char c, const uint32_t dval=0) { return seenval(c) ? value_ulong() : dval; }
|
||||
FORCE_INLINE static float linearval(const char c, const float dval=0.0) { return seenval(c) ? value_linear_units() : dval; }
|
||||
FORCE_INLINE static float celsiusval(const char c, const float dval=0.0) { return seenval(c) ? value_celsius() : dval; }
|
||||
FORCE_INLINE static float floatval(const char c, const float dval=0.0) { return seenval(c) ? value_float() : dval; }
|
||||
FORCE_INLINE static bool boolval(const char c) { return seenval(c) ? value_bool() : seen(c); }
|
||||
FORCE_INLINE static uint8_t byteval(const char c, const uint8_t dval=0) { return seenval(c) ? value_byte() : dval; }
|
||||
FORCE_INLINE static int16_t intval(const char c, const int16_t dval=0) { return seenval(c) ? value_int() : dval; }
|
||||
FORCE_INLINE static uint16_t ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort() : dval; }
|
||||
FORCE_INLINE static int32_t longval(const char c, const int32_t dval=0) { return seenval(c) ? value_long() : dval; }
|
||||
FORCE_INLINE static uint32_t ulongval(const char c, const uint32_t dval=0) { return seenval(c) ? value_ulong() : dval; }
|
||||
FORCE_INLINE static float linearval(const char c, const float dval=0.0) { return seenval(c) ? value_linear_units() : dval; }
|
||||
FORCE_INLINE static float celsiusval(const char c, const float dval=0.0) { return seenval(c) ? value_celsius() : dval; }
|
||||
FORCE_INLINE static const char* strval(const char c) { return seenval(c) ? value_ptr : NULL; }
|
||||
|
||||
};
|
||||
|
||||
|
Reference in New Issue
Block a user