Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ignore warning sign-compare in pin_is_protected #27261

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
34 changes: 17 additions & 17 deletions Marlin/src/HAL/AVR/pinsDebug.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,40 +42,40 @@
#define digitalPinToTimer_DEBUG(p) digitalPinToTimer(p)
#define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask(p)
#define digitalPinToPort_DEBUG(p) digitalPinToPort(p)
#define GET_PINMODE(pin) (*portModeRegister(pin) & digitalPinToBitMask_DEBUG(pin))
#define getValidPinMode(pin) (*portModeRegister(pin) & digitalPinToBitMask_DEBUG(pin))

#elif AVR_ATmega2560_FAMILY_PLUS_70 // So we can access/display all the pins on boards using more than 70

#include "pinsDebug_plus_70.h"
#define digitalPinToTimer_DEBUG(p) digitalPinToTimer_plus_70(p)
#define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask_plus_70(p)
#define digitalPinToPort_DEBUG(p) digitalPinToPort_plus_70(p)
bool GET_PINMODE(int8_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask_DEBUG(pin); }
bool getValidPinMode(pin_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask_DEBUG(pin); }

#else

#define digitalPinToTimer_DEBUG(p) digitalPinToTimer(p)
#define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask(p)
#define digitalPinToPort_DEBUG(p) digitalPinToPort(p)
bool GET_PINMODE(int8_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask_DEBUG(pin); }
#define GET_ARRAY_PIN(p) pgm_read_byte(&pin_array[p].pin)
bool getValidPinMode(pin_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask_DEBUG(pin); }
#define getPinByIndex(p) pgm_read_byte(&pin_array[p].pin)

#endif

#define VALID_PIN(pin) (pin >= 0 && pin < NUM_DIGITAL_PINS ? 1 : 0)
#define isValidPin(pin) (pin >= 0 && pin < NUM_DIGITAL_PINS ? 1 : 0)
#if AVR_ATmega1284_FAMILY
#define IS_ANALOG(P) WITHIN(P, analogInputToDigitalPin(7), analogInputToDigitalPin(0))
#define DIGITAL_PIN_TO_ANALOG_PIN(P) int(IS_ANALOG(P) ? (P) - analogInputToDigitalPin(7) : -1)
#define isAnalogPin(P) WITHIN(P, analogInputToDigitalPin(7), analogInputToDigitalPin(0))
#define digitalPinToAnalogIndex(P) int(isAnalogPin(P) ? (P) - analogInputToDigitalPin(7) : -1)
#else
#define _ANALOG1(P) WITHIN(P, analogInputToDigitalPin(0), analogInputToDigitalPin(7))
#define _ANALOG2(P) WITHIN(P, analogInputToDigitalPin(8), analogInputToDigitalPin(15))
#define IS_ANALOG(P) (_ANALOG1(P) || _ANALOG2(P))
#define DIGITAL_PIN_TO_ANALOG_PIN(P) int(_ANALOG1(P) ? (P) - analogInputToDigitalPin(0) : _ANALOG2(P) ? (P) - analogInputToDigitalPin(8) + 8 : -1)
#define isAnalogPin(P) (_ANALOG1(P) || _ANALOG2(P))
#define digitalPinToAnalogIndex(P) int(_ANALOG1(P) ? (P) - analogInputToDigitalPin(0) : _ANALOG2(P) ? (P) - analogInputToDigitalPin(8) + 8 : -1)
#endif
#define GET_ARRAY_PIN(p) pgm_read_byte(&pin_array[p].pin)
#define getPinByIndex(p) pgm_read_byte(&pin_array[p].pin)
#define MULTI_NAME_PAD 26 // space needed to be pretty if not first name assigned to a pin

void PRINT_ARRAY_NAME(uint8_t x) {
void printPinNameByIndex(uint8_t x) {
PGM_P const name_mem_pointer = (PGM_P)pgm_read_ptr(&pin_array[x].name);
for (uint8_t y = 0; y < MAX_NAME_LENGTH; ++y) {
char temp_char = pgm_read_byte(name_mem_pointer + y);
Expand All @@ -88,7 +88,7 @@ void PRINT_ARRAY_NAME(uint8_t x) {
}
}

#define GET_ARRAY_IS_DIGITAL(x) pgm_read_byte(&pin_array[x].is_digital)
#define getPinIsDigitalByIndex(x) pgm_read_byte(&pin_array[x].is_digital)

#if defined(__AVR_ATmega1284P__) // 1284 IDE extensions set this to the number of
#undef NUM_DIGITAL_PINS // digital only pins while all other CPUs have it
Expand Down Expand Up @@ -276,7 +276,7 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N -
if (TEST(*TMSK, TOIE)) err_prob_interrupt();
}

void pwm_details(uint8_t pin) {
void printPinPWM(uint8_t pin) {
switch (digitalPinToTimer_DEBUG(pin)) {

#if ABTEST(0)
Expand Down Expand Up @@ -347,7 +347,7 @@ void pwm_details(uint8_t pin) {
#else
UNUSED(print_is_also_tied);
#endif
} // pwm_details
} // printPinPWM

#ifndef digitalRead_mod // Use Teensyduino's version of digitalRead - it doesn't disable the PWMs
int digitalRead_mod(const pin_t pin) { // same as digitalRead except the PWM stop section has been removed
Expand All @@ -356,7 +356,7 @@ void pwm_details(uint8_t pin) {
}
#endif

void print_port(const pin_t pin) { // print port number
void printPinPort(const pin_t pin) { // print port number
#ifdef digitalPinToPort_DEBUG
uint8_t x;
SERIAL_ECHOPGM(" Port: ");
Expand Down Expand Up @@ -386,7 +386,7 @@ void print_port(const pin_t pin) { // print port number
#endif
}

#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)

#undef ABTEST
2 changes: 1 addition & 1 deletion Marlin/src/HAL/DUE/HAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ typedef Servo hal_servo_t;
#define HAL_ADC_RESOLUTION 10

#ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
#define analogInputToDigitalPin(p) pin_t((p < 12U) ? (p) + 54U : -1)
#endif

//
Expand Down
22 changes: 11 additions & 11 deletions Marlin/src/HAL/DUE/pinsDebug.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,19 +64,19 @@
#define NUMBER_PINS_TOTAL PINS_COUNT

#define digitalRead_mod(p) extDigitalRead(p) // AVR digitalRead disabled PWM before it read the pin
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
#define GET_ARRAY_PIN(p) pin_array[p].pin
#define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital
#define VALID_PIN(pin) (pin >= 0 && pin < int8_t(NUMBER_PINS_TOTAL))
#define DIGITAL_PIN_TO_ANALOG_PIN(p) int(p - analogInputToDigitalPin(0))
#define IS_ANALOG(P) WITHIN(P, char(analogInputToDigitalPin(0)), char(analogInputToDigitalPin(NUM_ANALOG_INPUTS - 1)))
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0)
#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
#define getPinByIndex(p) pin_array[p].pin
#define getPinIsDigitalByIndex(p) pin_array[p].is_digital
#define isValidPin(pin) (pin >= 0 && pin < int8_t(NUMBER_PINS_TOTAL))
#define digitalPinToAnalogIndex(p) int(p - analogInputToDigitalPin(0))
#define isAnalogPin(P) WITHIN(P, pin_t(analogInputToDigitalPin(0)), pin_t(analogInputToDigitalPin(NUM_ANALOG_INPUTS - 1)))
#define pwm_status(pin) (((g_pinStatus[pin] & 0xF) == PIN_STATUS_PWM) && \
((g_APinDescription[pin].ulPinAttribute & PIN_ATTR_PWM) == PIN_ATTR_PWM))
#define MULTI_NAME_PAD 14 // space needed to be pretty if not first name assigned to a pin

bool GET_PINMODE(int8_t pin) { // 1: output, 0: input
bool getValidPinMode(int8_t pin) { // 1: output, 0: input
volatile Pio* port = g_APinDescription[pin].pPort;
uint32_t mask = g_APinDescription[pin].ulPin;
uint8_t pin_status = g_pinStatus[pin] & 0xF;
Expand All @@ -85,14 +85,14 @@ bool GET_PINMODE(int8_t pin) { // 1: output, 0: input
|| pwm_status(pin));
}

void pwm_details(int32_t pin) {
void printPinPWM(int32_t pin) {
if (pwm_status(pin)) {
uint32_t chan = g_APinDescription[pin].ulPWMChannel;
SERIAL_ECHOPGM("PWM = ", PWM_INTERFACE->PWM_CH_NUM[chan].PWM_CDTY);
}
}

void print_port(const pin_t) {}
void printPinPort(const pin_t) {}

/**
* DUE Board pin | PORT | Label
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/HC32/HAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@
// Misc. Functions
//
#ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) (p)
#define analogInputToDigitalPin(p) pin_t(p)
#endif

#define CRITICAL_SECTION_START \
Expand Down
36 changes: 18 additions & 18 deletions Marlin/src/HAL/HC32/pinsDebug.h
Original file line number Diff line number Diff line change
Expand Up @@ -31,24 +31,24 @@

#define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS
#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS
#define VALID_PIN(pin) IS_GPIO_PIN(pin)
#define isValidPin(pin) IS_GPIO_PIN(pin)

// Note: pin_array is defined in `Marlin/src/pins/pinsDebug.h`, and since this file is included
// after it, it is available in this file as well.
#define GET_ARRAY_PIN(p) pin_t(pin_array[p].pin)
#define getPinByIndex(p) pin_t(pin_array[p].pin)
#define digitalRead_mod(p) extDigitalRead(p)
#define PRINT_PIN(p) \
#define printPinNumber(p) \
do { \
sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); \
SERIAL_ECHO(buffer); \
} while (0)
#define PRINT_PIN_ANALOG(p) \
#define printPinAnalog(p) \
do { \
sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); \
sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); \
SERIAL_ECHO(buffer); \
} while (0)
#define PRINT_PORT(p) print_port(p)
#define PRINT_ARRAY_NAME(x) \
#define PRINT_PORT(p) printPinPort(p)
#define printPinNameByIndex(x) \
do { \
sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); \
SERIAL_ECHO(buffer); \
Expand All @@ -71,28 +71,28 @@
#define M43_NEVER_TOUCH(Q) (IS_HOST_USART_PIN(Q) || IS_OSC_PIN(Q))
#endif

static pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) {
if (!VALID_PIN(pin)) return -1;
static pin_t digitalPinToAnalogIndex(pin_t pin) {
if (!isValidPin(pin)) return -1;
const int8_t adc_channel = int8_t(PIN_MAP[pin].adc_info.channel);
return pin_t(adc_channel);
}

static bool IS_ANALOG(pin_t pin) {
if (!VALID_PIN(pin)) return false;
static bool isAnalogPin(pin_t pin) {
if (!isValidPin(pin)) return false;

if (PIN_MAP[pin].adc_info.channel != ADC_PIN_INVALID)
return _GET_MODE(pin) == INPUT_ANALOG && !M43_NEVER_TOUCH(pin);

return false;
}

static bool GET_PINMODE(const pin_t pin) {
return VALID_PIN(pin) && !IS_INPUT(pin);
static bool getValidPinMode(const pin_t pin) {
return isValidPin(pin) && !IS_INPUT(pin);
}

static bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) {
const pin_t pin = GET_ARRAY_PIN(array_pin);
return (!IS_ANALOG(pin));
static bool getPinIsDigitalByIndex(const int16_t array_pin) {
const pin_t pin = getPinByIndex(array_pin);
return (!isAnalogPin(pin));
}

/**
Expand All @@ -117,7 +117,7 @@ bool pwm_status(const pin_t pin) {
return timera_is_unit_initialized(unit) && timera_is_channel_active(unit, channel) && getPinMode(pin) == OUTPUT_PWM;
}

void pwm_details(const pin_t pin) {
void printPinPWM(const pin_t pin) {
// Get timer assignment for pin
timera_config_t *unit;
en_timera_channel_t channel;
Expand Down Expand Up @@ -161,7 +161,7 @@ void pwm_details(const pin_t pin) {
}
}

void print_port(pin_t pin) {
void printPinPort(pin_t pin) {
const char port = 'A' + char(pin >> 4); // Pin div 16
const int16_t gbit = PIN_MAP[pin].bit_pos;
char buffer[8];
Expand Down
2 changes: 1 addition & 1 deletion Marlin/src/HAL/LINUX/HAL.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ uint8_t MarlinHAL::active_ch = 0;

uint16_t MarlinHAL::adc_value() {
const pin_t pin = analogInputToDigitalPin(active_ch);
if (!VALID_PIN(pin)) return 0;
if (!isValidPin(pin)) return 0;
return uint16_t((Gpio::get(pin) >> 2) & 0x3FF); // return 10bit value as Marlin expects
}

Expand Down
12 changes: 6 additions & 6 deletions Marlin/src/HAL/LINUX/arduino.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,28 +49,28 @@ extern "C" void delay(const int msec) {
// IO functions
// As defined by Arduino INPUT(0x0), OUTPUT(0x1), INPUT_PULLUP(0x2)
void pinMode(const pin_t pin, const uint8_t mode) {
if (!VALID_PIN(pin)) return;
if (!isValidPin(pin)) return;
Gpio::setMode(pin, mode);
}

void digitalWrite(pin_t pin, uint8_t pin_status) {
if (!VALID_PIN(pin)) return;
if (!isValidPin(pin)) return;
Gpio::set(pin, pin_status);
}

bool digitalRead(pin_t pin) {
if (!VALID_PIN(pin)) return false;
if (!isValidPin(pin)) return false;
return Gpio::get(pin);
}

void analogWrite(pin_t pin, int pwm_value) { // 1 - 254: pwm_value, 0: LOW, 255: HIGH
if (!VALID_PIN(pin)) return;
if (!isValidPin(pin)) return;
Gpio::set(pin, pwm_value);
}

uint16_t analogRead(pin_t adc_pin) {
if (!VALID_PIN(DIGITAL_PIN_TO_ANALOG_PIN(adc_pin))) return 0;
return Gpio::get(DIGITAL_PIN_TO_ANALOG_PIN(adc_pin));
if (!isValidPin(digitalPinToAnalogIndex(adc_pin))) return 0;
return Gpio::get(digitalPinToAnalogIndex(adc_pin));
}

char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s) {
Expand Down
4 changes: 2 additions & 2 deletions Marlin/src/HAL/LINUX/include/pinmapping.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,15 +42,15 @@ constexpr pin_t analogInputToDigitalPin(const int8_t p) {
}

// Get the analog index for a digital pin
constexpr int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t p) {
constexpr int8_t digitalPinToAnalogIndex(const pin_t p) {
return (WITHIN(p, analog_offset, NUM_DIGITAL_PINS) ? p - analog_offset : P_NC);
}

// Return the index of a pin number
constexpr int16_t GET_PIN_MAP_INDEX(const pin_t pin) { return pin; }

// Test whether the pin is valid
constexpr bool VALID_PIN(const pin_t p) { return WITHIN(p, 0, NUM_DIGITAL_PINS); }
constexpr bool isValidPin(const pin_t p) { return WITHIN(p, 0, NUM_DIGITAL_PINS); }

// Test whether the pin is PWM
constexpr bool PWM_PIN(const pin_t p) { return false; }
Expand Down
22 changes: 11 additions & 11 deletions Marlin/src/HAL/LINUX/pinsDebug.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,32 +29,32 @@
*/

#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
#define IS_ANALOG(P) (DIGITAL_PIN_TO_ANALOG_PIN(P) >= 0 ? 1 : 0)
#define isAnalogPin(P) (digitalPinToAnalogIndex(P) >= 0 ? 1 : 0)
#define digitalRead_mod(p) digitalRead(p)
#define GET_ARRAY_PIN(p) pin_array[p].pin
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
#define getPinByIndex(p) pin_array[p].pin
#define printPinNameByIndex(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define printPinNumber(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
#define printPinAnalog(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), digitalPinToAnalogIndex(pin)); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin

// active ADC function/mode/code values for PINSEL registers
constexpr int8_t ADC_pin_mode(pin_t pin) { return -1; }

int8_t get_pin_mode(const pin_t pin) { return VALID_PIN(pin) ? 0 : -1; }
int8_t get_pin_mode(const pin_t pin) { return isValidPin(pin) ? 0 : -1; }

bool GET_PINMODE(const pin_t pin) {
bool getValidPinMode(const pin_t pin) {
const int8_t pin_mode = get_pin_mode(pin);
if (pin_mode == -1 || pin_mode == ADC_pin_mode(pin)) // Invalid pin or active analog pin
return false;

return (Gpio::getMode(pin) != 0); // Input/output state
}

bool GET_ARRAY_IS_DIGITAL(const pin_t pin) {
return (!IS_ANALOG(pin) || get_pin_mode(pin) != ADC_pin_mode(pin));
bool getPinIsDigitalByIndex(const pin_t pin) {
return (!isAnalogPin(pin) || get_pin_mode(pin) != ADC_pin_mode(pin));
}

void pwm_details(const pin_t pin) {}
void printPinPWM(const pin_t pin) {}
bool pwm_status(const pin_t) { return false; }

void print_port(const pin_t) {}
void printPinPort(const pin_t) {}
4 changes: 2 additions & 2 deletions Marlin/src/HAL/LPC1768/HAL.h
Original file line number Diff line number Diff line change
Expand Up @@ -137,12 +137,12 @@ extern DefaultSerial1 USBSerial;
//

// Test whether the pin is valid
constexpr bool VALID_PIN(const pin_t pin) {
constexpr bool isValidPin(const pin_t pin) {
return LPC176x::pin_is_valid(pin);
}

// Get the analog index for a digital pin
constexpr int8_t DIGITAL_PIN_TO_ANALOG_PIN(const pin_t pin) {
constexpr int8_t digitalPinToAnalogIndex(const pin_t pin) {
return (LPC176x::pin_is_valid(pin) && LPC176x::pin_has_adc(pin)) ? pin : -1;
}

Expand Down
Loading
Loading