️ Refactor still needs work

Reverting #23295
This commit is contained in:
Scott Lahteine
2021-12-25 23:15:17 -06:00
parent 00e6e90648
commit 6a8b9274a3
69 changed files with 1301 additions and 1771 deletions

View File

@@ -24,12 +24,6 @@
#include "../../inc/MarlinConfig.h"
#include "../shared/Delay.h"
extern MarlinHAL hal;
// ------------------------
// Serial ports
// ------------------------
MSerialT usb_serial(TERN0(EMERGENCY_PARSER, true));
// U8glib required functions
@@ -43,21 +37,42 @@ extern "C" {
//************************//
// return free heap space
int freeMemory() { return 0; }
int freeMemory() {
return 0;
}
// ------------------------
// ADC
// ------------------------
uint8_t MarlinHAL::active_ch = 0;
void HAL_adc_init() {
uint16_t MarlinHAL::adc_value() {
const pin_t pin = analogInputToDigitalPin(active_ch);
}
void HAL_adc_enable_channel(const uint8_t ch) {
}
uint8_t active_ch = 0;
void HAL_adc_start_conversion(const uint8_t ch) {
active_ch = ch;
}
bool HAL_adc_finished() {
return true;
}
uint16_t HAL_adc_get_result() {
pin_t pin = analogInputToDigitalPin(active_ch);
if (!VALID_PIN(pin)) return 0;
const uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF);
uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF);
return data; // return 10bit value as Marlin expects
}
void MarlinHAL::reboot() { /* Reset the application state and GPIO */ }
void HAL_pwm_init() {
}
void HAL_reboot() { /* Reset the application state and GPIO */ }
#endif // __PLAT_LINUX__

View File

@@ -21,42 +21,25 @@
*/
#pragma once
#include <iostream>
#include <stdint.h>
#include <stdarg.h>
#undef min
#undef max
#include <algorithm>
#include "hardware/Clock.h"
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include "watchdog.h"
#include "serial.h"
// ------------------------
// Defines
// ------------------------
#define CPU_32_BIT
#define SHARED_SERVOS HAS_SERVOS // Use shared/servos.cpp
#define F_CPU 100000000UL
#define SystemCoreClock F_CPU
#include <iostream>
#include <stdint.h>
#include <stdarg.h>
#define DELAY_CYCLES(x) Clock::delayCycles(x)
#undef min
#undef max
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
#include <algorithm>
void _printf(const char *format, ...);
void _printf (const char *format, ...);
void _putc(uint8_t c);
uint8_t _getc();
//extern "C" volatile uint32_t _millis;
//arduino: Print.h
#define DEC 10
#define HEX 16
@@ -66,27 +49,36 @@ uint8_t _getc();
#define B01 1
#define B10 2
// ------------------------
// Serial ports
// ------------------------
#include "hardware/Clock.h"
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include "watchdog.h"
#include "serial.h"
#define SHARED_SERVOS HAS_SERVOS
extern MSerialT usb_serial;
#define MYSERIAL1 usb_serial
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
//
// Interrupts
//
#define CRITICAL_SECTION_START()
#define CRITICAL_SECTION_END()
#define ISRS_ENABLED()
#define ENABLE_ISRS()
#define DISABLE_ISRS()
// ADC
#define HAL_ADC_VREF 5.0
#define HAL_ADC_RESOLUTION 10
// ------------------------
// Class Utilities
// ------------------------
inline void HAL_init() {}
// Utility functions
#pragma GCC diagnostic push
#if GCC_VERSION <= 50000
#pragma GCC diagnostic ignored "-Wunused-function"
@@ -96,67 +88,29 @@ int freeMemory();
#pragma GCC diagnostic pop
// ------------------------
// MarlinHAL Class
// ------------------------
// ADC
#define HAL_ADC_VREF 5.0
#define HAL_ADC_RESOLUTION 10
#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch)
#define HAL_START_ADC(ch) HAL_adc_start_conversion(ch)
#define HAL_READ_ADC() HAL_adc_get_result()
#define HAL_ADC_READY() true
class MarlinHAL {
public:
void HAL_adc_init();
void HAL_adc_enable_channel(const uint8_t ch);
void HAL_adc_start_conversion(const uint8_t ch);
uint16_t HAL_adc_get_result();
// Earliest possible init, before setup()
MarlinHAL() {}
// PWM
inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
static inline void init() {} // Called early in setup()
static inline void init_board() {} // Called less early in setup()
static void reboot(); // Reset the application state and GPIO
// Reset source
inline void HAL_clear_reset_source(void) {}
inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
static inline bool isr_state() { return true; }
static inline void isr_on() {}
static inline void isr_off() {}
void HAL_reboot(); // Reset the application state and GPIO
static inline void delay_ms(const int ms) { _delay_ms(ms); }
// Tasks, called from idle()
static inline void idletask() {}
// Reset
static constexpr uint8_t reset_reason = RST_POWER_ON;
static inline uint8_t get_reset_source() { return reset_reason; }
static inline void clear_reset_source() {}
// Free SRAM
static inline int freeMemory() { return ::freeMemory(); }
//
// ADC Methods
//
static uint8_t active_ch;
// Called by Temperature::init once at startup
static inline void adc_init() {}
// Called by Temperature::init for each sensor at startup
static inline void adc_enable(const uint8_t) {}
// Begin ADC sampling on the given channel
static inline void adc_start(const uint8_t ch) { active_ch = ch; }
// Is the ADC ready for reading?
static inline bool adc_ready() { return true; }
// The current value of the ADC register
static uint16_t adc_value();
/**
* Set the PWM duty cycle for the pin to the given value.
* No option to change the resolution or invert the duty cycle.
*/
static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
analogWrite(pin, v);
}
static inline void set_pwm_frequency(const pin_t, int) {}
};
extern MarlinHAL hal;
/* ---------------- Delay in cycles */
FORCE_INLINE static void DELAY_CYCLES(uint64_t x) {
Clock::delayCycles(x);
}

View File

@@ -31,7 +31,9 @@ void cli() { } // Disable
void sei() { } // Enable
// Time functions
void _delay_ms(const int ms) { delay(ms); }
void _delay_ms(const int delay_ms) {
delay(delay_ms);
}
uint32_t millis() {
return (uint32_t)Clock::millis();

View File

@@ -59,6 +59,7 @@ typedef uint8_t byte;
#endif
#define sq(v) ((v) * (v))
#define square(v) sq(v)
#define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value)))
//Interrupts
@@ -73,8 +74,8 @@ extern "C" {
}
// Time functions
extern "C" void delay(const int ms);
void _delay_ms(const int ms);
extern "C" void delay(const int milis);
void _delay_ms(const int delay);
void delayMicroseconds(unsigned long);
uint32_t millis();

View File

@@ -92,5 +92,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num);
void HAL_timer_disable_interrupt(const uint8_t timer_num);
bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
#define HAL_timer_isr_prologue(T) NOOP
#define HAL_timer_isr_epilogue(T) NOOP
#define HAL_timer_isr_prologue(T)
#define HAL_timer_isr_epilogue(T)