STM32F1: M43 PINS_DEBUGGING (#14072)
This commit is contained in:
parent
81d550754a
commit
52383633e7
|
@ -32,9 +32,10 @@
|
||||||
// --------------------------------------------------------------------------
|
// --------------------------------------------------------------------------
|
||||||
|
|
||||||
#include "HAL.h"
|
#include "HAL.h"
|
||||||
#include <STM32ADC.h>
|
|
||||||
#include "../../inc/MarlinConfig.h"
|
#include "../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
#include <STM32ADC.h>
|
||||||
|
|
||||||
// --------------------------------------------------------------------------
|
// --------------------------------------------------------------------------
|
||||||
// Externals
|
// Externals
|
||||||
// --------------------------------------------------------------------------
|
// --------------------------------------------------------------------------
|
||||||
|
@ -314,4 +315,15 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
|
||||||
|
|
||||||
uint16_t HAL_adc_get_result(void) { return HAL_adc_result; }
|
uint16_t HAL_adc_get_result(void) { return HAL_adc_result; }
|
||||||
|
|
||||||
|
uint16_t analogRead(pin_t pin) {
|
||||||
|
const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG;
|
||||||
|
return is_analog ? analogRead(uint8_t(pin)) : 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Wrapper to maple unprotected analogWrite
|
||||||
|
void analogWrite(pin_t pin, int pwm_val8) {
|
||||||
|
if (PWM_PIN(pin) && IS_OUTPUT(pin))
|
||||||
|
analogWrite(uint8_t(pin), pwm_val8);
|
||||||
|
}
|
||||||
|
|
||||||
#endif // __STM32F1__
|
#endif // __STM32F1__
|
||||||
|
|
|
@ -255,6 +255,9 @@ void HAL_adc_init(void);
|
||||||
void HAL_adc_start_conversion(const uint8_t adc_pin);
|
void HAL_adc_start_conversion(const uint8_t adc_pin);
|
||||||
uint16_t HAL_adc_get_result(void);
|
uint16_t HAL_adc_get_result(void);
|
||||||
|
|
||||||
|
uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first
|
||||||
|
void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!?
|
||||||
|
|
||||||
#define GET_PIN_MAP_PIN(index) index
|
#define GET_PIN_MAP_PIN(index) index
|
||||||
#define GET_PIN_MAP_INDEX(pin) pin
|
#define GET_PIN_MAP_INDEX(pin) pin
|
||||||
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
|
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
|
||||||
|
|
|
@ -1 +1,127 @@
|
||||||
#error Debug pins is not supported on this Platform!
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Support routines for STM32F1
|
||||||
|
*/
|
||||||
|
#ifdef __STM32F1__
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Translation of routines & variables used by pinsDebug.h
|
||||||
|
*/
|
||||||
|
#include "fastio_STM32F1.h"
|
||||||
|
|
||||||
|
extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS];
|
||||||
|
|
||||||
|
#define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS
|
||||||
|
#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS
|
||||||
|
#define VALID_PIN(pin) (pin >= 0 && pin < BOARD_NR_GPIO_PINS)
|
||||||
|
#define GET_ARRAY_PIN(p) pin_t(pin_array[p].pin)
|
||||||
|
#define pwm_status(pin) PWM_PIN(pin)
|
||||||
|
#define digitalRead_mod(p) extDigitalRead(p)
|
||||||
|
#define NAME_FORMAT(p) PSTR("%-##p##s")
|
||||||
|
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); SERIAL_ECHO(buffer); }while(0)
|
||||||
|
#define PRINT_PORT(p) print_port(p)
|
||||||
|
#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 MULTI_NAME_PAD 20 // spaces needed to be pretty if not first name assigned to a pin
|
||||||
|
|
||||||
|
// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
|
||||||
|
#ifndef M43_NEVER_TOUCH
|
||||||
|
#define M43_NEVER_TOUCH(Q) (Q >= 9 && Q <= 12) // SERIAL/USB pins PA9(TX) PA10(RX)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
static inline int8_t get_pin_mode(pin_t pin) {
|
||||||
|
return VALID_PIN(pin) ? _GET_MODE(pin) : -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) {
|
||||||
|
if (!VALID_PIN(pin)) return -1;
|
||||||
|
int8_t adc_channel = int8_t(PIN_MAP[pin].adc_channel);
|
||||||
|
#ifdef NUM_ANALOG_INPUTS
|
||||||
|
if (adc_channel >= NUM_ANALOG_INPUTS) adc_channel = ADCx;
|
||||||
|
#endif
|
||||||
|
return pin_t(adc_channel);
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline bool IS_ANALOG(pin_t pin) {
|
||||||
|
if (!VALID_PIN(pin)) return false;
|
||||||
|
if (PIN_MAP[pin].adc_channel != ADCx) {
|
||||||
|
#ifdef NUM_ANALOG_INPUTS
|
||||||
|
if (PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS) return false;
|
||||||
|
#endif
|
||||||
|
return _GET_MODE(pin) == GPIO_INPUT_ANALOG && !M43_NEVER_TOUCH(pin);
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline bool GET_PINMODE(pin_t pin) {
|
||||||
|
return VALID_PIN(pin) ? !IS_INPUT(pin) : false;
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline bool GET_ARRAY_IS_DIGITAL(int16_t array_pin) {
|
||||||
|
pin_t pin = GET_ARRAY_PIN(array_pin);
|
||||||
|
bool isDigital = !IS_ANALOG(pin);
|
||||||
|
#ifdef NUM_ANALOG_INPUTS
|
||||||
|
if (!isDigital && PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS)
|
||||||
|
isDigital = true;
|
||||||
|
#endif
|
||||||
|
return isDigital;
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline void pwm_details(pin_t pin) {
|
||||||
|
if (PWM_PIN(pin)) {
|
||||||
|
char buffer[16], num = '?';
|
||||||
|
timer_dev * const tdev = PIN_MAP[pin].timer_device;
|
||||||
|
const uint8_t channel = PIN_MAP[pin].timer_channel;
|
||||||
|
if (tdev == &timer1) num = '1';
|
||||||
|
else if (tdev == &timer1) num = '1';
|
||||||
|
else if (tdev == &timer2) num = '2';
|
||||||
|
else if (tdev == &timer3) num = '3';
|
||||||
|
else if (tdev == &timer4) num = '4';
|
||||||
|
#ifdef STM32_HIGH_DENSITY
|
||||||
|
else if (tdev == &timer5) num = '5';
|
||||||
|
else if (tdev == &timer8) num = '8';
|
||||||
|
#endif
|
||||||
|
sprintf_P(buffer, PSTR(" TIM%c CH%c"), num, ('0' + channel));
|
||||||
|
SERIAL_ECHO(buffer);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static inline void print_port(pin_t pin) {
|
||||||
|
char buffer[8];
|
||||||
|
char port = 'A' + char(pin >> 4); // pin div 16
|
||||||
|
/* seems not to be required for our devices
|
||||||
|
gpio_dev* gp = PIN_MAP[pin].gpio_device;
|
||||||
|
if (gp == &gpioa) port = 'A';
|
||||||
|
else if (gp == &gpiob) port = 'B';
|
||||||
|
else if (gp == &gpioc) port = 'C';
|
||||||
|
else if (gp == &gpiod) port = 'D';
|
||||||
|
#if STM32_NR_GPIO_PORTS > 4
|
||||||
|
else if (gp == &gpioe) port = 'E';
|
||||||
|
else if (gp == &gpiof) port = 'F';
|
||||||
|
else if (gp == &gpiog) port = 'G';
|
||||||
|
#endif
|
||||||
|
*/
|
||||||
|
const int16_t gbit = PIN_MAP[pin].gpio_bit;
|
||||||
|
sprintf_P(buffer, PSTR("P%c%hd "), port, gbit);
|
||||||
|
if (gbit < 10) SERIAL_CHAR(' ');
|
||||||
|
SERIAL_ECHO(buffer);
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // __STM32F1__
|
||||||
|
|
|
@ -118,7 +118,9 @@ void LEDLights::set_color(const LEDColor &incol
|
||||||
|
|
||||||
// This variant uses 3-4 separate pins for the RGB(W) components.
|
// This variant uses 3-4 separate pins for the RGB(W) components.
|
||||||
// If the pins can do PWM then their intensity will be set.
|
// If the pins can do PWM then their intensity will be set.
|
||||||
#define UPDATE_RGBW(C,c) do{ if (PWM_PIN(RGB_LED_##C##_PIN)) analogWrite(RGB_LED_##C##_PIN, incol.c); else WRITE(RGB_LED_##C##_PIN, incol.c ? HIGH : LOW); }while(0)
|
#define UPDATE_RGBW(C,c) do { if (PWM_PIN(RGB_LED_##C##_PIN)) \
|
||||||
|
analogWrite(pin_t(RGB_LED_##C##_PIN), incol.c); \
|
||||||
|
else WRITE(RGB_LED_##C##_PIN, incol.c ? HIGH : LOW); } while(0)
|
||||||
UPDATE_RGBW(R,r);
|
UPDATE_RGBW(R,r);
|
||||||
UPDATE_RGBW(G,g);
|
UPDATE_RGBW(G,g);
|
||||||
UPDATE_RGBW(B,b);
|
UPDATE_RGBW(B,b);
|
||||||
|
|
|
@ -896,7 +896,7 @@ void Endstops::update() {
|
||||||
ES_REPORT_CHANGE(Z3_MAX);
|
ES_REPORT_CHANGE(Z3_MAX);
|
||||||
#endif
|
#endif
|
||||||
SERIAL_ECHOLNPGM("\n");
|
SERIAL_ECHOLNPGM("\n");
|
||||||
analogWrite(LED_PIN, local_LED_status);
|
analogWrite(pin_t(LED_PIN), local_LED_status);
|
||||||
local_LED_status ^= 255;
|
local_LED_status ^= 255;
|
||||||
old_live_state_local = live_state_local;
|
old_live_state_local = live_state_local;
|
||||||
}
|
}
|
||||||
|
|
|
@ -1294,13 +1294,13 @@ void Planner::check_axes_activity() {
|
||||||
#else
|
#else
|
||||||
|
|
||||||
#if HAS_FAN0
|
#if HAS_FAN0
|
||||||
analogWrite(FAN_PIN, CALC_FAN_SPEED(0));
|
analogWrite(pin_t(FAN_PIN), CALC_FAN_SPEED(0));
|
||||||
#endif
|
#endif
|
||||||
#if HAS_FAN1
|
#if HAS_FAN1
|
||||||
analogWrite(FAN1_PIN, CALC_FAN_SPEED(1));
|
analogWrite(pin_t(FAN1_PIN), CALC_FAN_SPEED(1));
|
||||||
#endif
|
#endif
|
||||||
#if HAS_FAN2
|
#if HAS_FAN2
|
||||||
analogWrite(FAN2_PIN, CALC_FAN_SPEED(2));
|
analogWrite(pin_t(FAN2_PIN), CALC_FAN_SPEED(2));
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#else
|
#else
|
||||||
|
|
Loading…
Reference in a new issue