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:
@@ -23,6 +23,7 @@
|
||||
#ifdef TARGET_LPC1768
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "LPC1768_PWM.h"
|
||||
|
||||
#include <lpc17xx_pinsel.h>
|
||||
|
||||
@@ -70,26 +71,26 @@ extern "C" void delay(const int msec) {
|
||||
|
||||
// IO functions
|
||||
// As defined by Arduino INPUT(0x0), OUPUT(0x1), INPUT_PULLUP(0x2)
|
||||
void pinMode(uint8_t pin, uint8_t mode) {
|
||||
if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
|
||||
void pinMode(pin_t pin, uint8_t mode) {
|
||||
if (!VALID_PIN(pin))
|
||||
return;
|
||||
|
||||
PINSEL_CFG_Type config = { pin_map[pin].port,
|
||||
pin_map[pin].pin,
|
||||
PINSEL_CFG_Type config = { LPC1768_PIN_PORT(pin),
|
||||
LPC1768_PIN_PIN(pin),
|
||||
PINSEL_FUNC_0,
|
||||
PINSEL_PINMODE_TRISTATE,
|
||||
PINSEL_PINMODE_NORMAL };
|
||||
switch(mode) {
|
||||
case INPUT:
|
||||
LPC_GPIO(pin_map[pin].port)->FIODIR &= ~LPC_PIN(pin_map[pin].pin);
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
PINSEL_ConfigPin(&config);
|
||||
break;
|
||||
case OUTPUT:
|
||||
LPC_GPIO(pin_map[pin].port)->FIODIR |= LPC_PIN(pin_map[pin].pin);
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR |= LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
PINSEL_ConfigPin(&config);
|
||||
break;
|
||||
case INPUT_PULLUP:
|
||||
LPC_GPIO(pin_map[pin].port)->FIODIR &= ~LPC_PIN(pin_map[pin].pin);
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIODIR &= ~LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
config.Pinmode = PINSEL_PINMODE_PULLUP;
|
||||
PINSEL_ConfigPin(&config);
|
||||
break;
|
||||
@@ -98,14 +99,14 @@ void pinMode(uint8_t pin, uint8_t mode) {
|
||||
}
|
||||
}
|
||||
|
||||
void digitalWrite(uint8_t pin, uint8_t pin_status) {
|
||||
if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
|
||||
void digitalWrite(pin_t pin, uint8_t pin_status) {
|
||||
if (!VALID_PIN(pin))
|
||||
return;
|
||||
|
||||
if (pin_status)
|
||||
LPC_GPIO(pin_map[pin].port)->FIOSET = LPC_PIN(pin_map[pin].pin);
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOSET = LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
else
|
||||
LPC_GPIO(pin_map[pin].port)->FIOCLR = LPC_PIN(pin_map[pin].pin);
|
||||
LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOCLR = LPC_PIN(LPC1768_PIN_PIN(pin));
|
||||
|
||||
pinMode(pin, OUTPUT); // Set pin mode on every write (Arduino version does this)
|
||||
|
||||
@@ -118,23 +119,19 @@ void digitalWrite(uint8_t pin, uint8_t pin_status) {
|
||||
*/
|
||||
}
|
||||
|
||||
bool digitalRead(uint8_t pin) {
|
||||
if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF) {
|
||||
bool digitalRead(pin_t pin) {
|
||||
if (!VALID_PIN(pin)) {
|
||||
return false;
|
||||
}
|
||||
return LPC_GPIO(pin_map[pin].port)->FIOPIN & LPC_PIN(pin_map[pin].pin) ? 1 : 0;
|
||||
return LPC_GPIO(LPC1768_PIN_PORT(pin))->FIOPIN & LPC_PIN(LPC1768_PIN_PIN(pin)) ? 1 : 0;
|
||||
}
|
||||
|
||||
void analogWrite(uint8_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255: HIGH
|
||||
|
||||
extern bool LPC1768_PWM_attach_pin(uint8_t, uint32_t, uint32_t, uint8_t);
|
||||
extern bool LPC1768_PWM_write(uint8_t, uint32_t);
|
||||
extern bool LPC1768_PWM_detach_pin(uint8_t);
|
||||
void analogWrite(pin_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255: HIGH
|
||||
#define MR0_MARGIN 200 // if channel value too close to MR0 the system locks up
|
||||
|
||||
static bool out_of_PWM_slots = false;
|
||||
|
||||
if (!WITHIN(pin, 0, NUM_DIGITAL_PINS - 1) || pin_map[pin].port == 0xFF)
|
||||
if (!VALID_PIN(pin))
|
||||
return;
|
||||
|
||||
uint value = MAX(MIN(pwm_value, 255), 0);
|
||||
@@ -155,7 +152,7 @@ void analogWrite(uint8_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 2
|
||||
|
||||
extern bool HAL_adc_finished();
|
||||
|
||||
uint16_t analogRead(uint8_t adc_pin) {
|
||||
uint16_t analogRead(pin_t adc_pin) {
|
||||
HAL_adc_start_conversion(adc_pin);
|
||||
while (!HAL_adc_finished()); // Wait for conversion to finish
|
||||
return HAL_adc_get_result();
|
||||
|
||||
Reference in New Issue
Block a user